diff --git a/.cproject b/.cproject index 0acb12e7e..1f29f86b7 100644 --- a/.cproject +++ b/.cproject @@ -433,166 +433,6 @@ false true - - make - -j2 - check - true - true - true - - - make - -j2 - testGaussianFactorGraph.run - true - true - true - - - make - -j2 - testGaussianISAM.run - true - true - true - - - make - - testGraph.run - true - false - true - - - make - -j2 - testIterative.run - true - true - true - - - make - -j2 - testNonlinearEquality.run - true - true - true - - - make - -j2 - testNonlinearFactor.run - true - true - true - - - make - -j2 - testNonlinearFactorGraph.run - true - true - true - - - make - -j2 - testNonlinearOptimizer.run - true - true - true - - - make - -j2 - testSubgraphPreconditioner.run - true - true - true - - - make - -j2 - testTupleConfig.run - true - true - true - - - make - -j2 - timeGaussianFactorGraph.run - true - true - true - - - make - - testInference.run - true - false - true - - - make - - testGaussianFactor.run - true - false - true - - - make - - testJunctionTree.run - true - false - true - - - make - - testSymbolicBayesNet.run - true - false - true - - - make - - testSymbolicFactorGraph.run - true - false - true - - - make - -j2 - clean - true - true - true - - - make - -j2 - testGaussianJunctionTree - true - true - true - - - make - -j2 - testSerialization.run - true - true - true - make -j5 @@ -737,34 +577,82 @@ true true - + make - -j2 - tests/testGeneralSFMFactor.run + -j5 + testGeneralSFMFactor.run true true true - + make - -j2 - tests/testPlanarSLAM.run + -j5 + testPlanarSLAM.run true true true - + make - -j2 - tests/testPose2SLAM.run + -j5 + testPose2SLAM.run true true true - + make - -j2 - tests/testPose3SLAM.run + -j5 + testPose3SLAM.run + true + true + true + + + make + -j5 + testSimulated2D.run + true + true + true + + + make + -j5 + testSimulated2DOriented.run + true + true + true + + + make + -j5 + testVisualSLAM.run + true + true + true + + + make + -j5 + testProjectionFactor.run + true + true + true + + + make + -j5 + testSerializationSLAM.run + true + true + true + + + make + -j5 + testGeneralSFMFactor_Cal3Bundler.run true true true @@ -897,22 +785,6 @@ true true - - make - -j2 - testGaussianJunctionTree.run - true - true - true - - - make - -j2 - testGaussianFactorGraph.run - true - true - true - make -j2 @@ -921,42 +793,26 @@ true true - + make - -j2 - testTupleConfig.run + -j5 + testMarginals.run true true true - + make - -j2 - testSerialization.run + -j5 + testGaussianISAM2.run true true true - + make - -j2 - testInference.run - true - true - true - - - make - -j2 - testGaussianISAM.run - true - true - true - - - make - -j2 - testSymbolicFactorGraph.run + -j5 + testSymbolicFactorGraphB.run true true true @@ -985,14 +841,6 @@ true true - - make - -j2 - testPose2SLAMwSPCG.run - true - true - true - make -j2 @@ -1017,14 +865,6 @@ true true - - make - -j5 - tests.testBoundingConstraint.run - true - true - true - make -j2 @@ -1057,6 +897,59 @@ true true + + make + -j5 + clean + true + true + true + + + make + -j5 + testGaussianJunctionTreeB.run + true + true + true + + + make + testGraph.run + true + false + true + + + make + testJunctionTree.run + true + false + true + + + make + testSymbolicBayesNetB.run + true + false + true + + + make + -j5 + testGaussianISAM.run + true + true + true + + + make + -j5 + testDoglegOptimizer.run + true + true + true + make -j2 @@ -1752,18 +1645,18 @@ true true - + make - -j2 - CameraResectioning + -j5 + CameraResectioning.run true true true - + make - -j2 - PlanarSLAMExample_easy.run + -j5 + PlanarSLAMExample.run true true true @@ -1792,10 +1685,10 @@ true true - + make - -j2 - PlanarSLAMSelfContained_advanced.run + -j5 + PlanarSLAMExample_selfcontained.run true true true @@ -1808,18 +1701,18 @@ true true - + make - -j2 - Pose2SLAMExample_easy.run + -j5 + Pose2SLAMExample.run true true true - + make - -j2 - Pose2SLAMwSPCG_easy.run + -j5 + Pose2SLAMwSPCG.run true true true @@ -1832,6 +1725,30 @@ true true + + make + -j5 + LocalizationExample.run + true + true + true + + + make + -j5 + LocalizationExample2.run + true + true + true + + + make + -j5 + Pose2SLAMExample_graph.run + true + true + true + make -j2 diff --git a/Doxyfile b/Doxyfile index d7dd6adff..2d1dab711 100644 --- a/Doxyfile +++ b/Doxyfile @@ -597,7 +597,7 @@ WARNINGS = YES # for undocumented members. If EXTRACT_ALL is set to YES then this flag will # automatically be disabled. -WARN_IF_UNDOCUMENTED = YES +WARN_IF_UNDOCUMENTED = NO # If WARN_IF_DOC_ERROR is set to YES, doxygen will generate warnings for # potential errors in the documentation, such as not documenting some diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index f92312296..a54c8366c 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -30,4 +30,3 @@ foreach(example_src ${example_srcs} ) endforeach(example_src) -add_subdirectory(vSLAMexample) diff --git a/examples/CameraResectioning.cpp b/examples/CameraResectioning.cpp index 0280a4f8d..3f586a67f 100644 --- a/examples/CameraResectioning.cpp +++ b/examples/CameraResectioning.cpp @@ -17,88 +17,81 @@ */ #include -#include -#include -#include -#include -#include #include +#include +#include using namespace gtsam; +using symbol_shorthand::X; /** - * Unary factor for the pose. + * Unary factor on the unknown pose, resulting from meauring the projection of + * a known 3D point in the image */ class ResectioningFactor: public NoiseModelFactor1 { - typedef NoiseModelFactor1 Base; + typedef NoiseModelFactor1 Base; - shared_ptrK K_; // camera's intrinsic parameters - Point3 P_; // 3D point on the calibration rig - Point2 p_; // 2D measurement of the 3D point + shared_ptrK K_; // camera's intrinsic parameters + Point3 P_; // 3D point on the calibration rig + Point2 p_; // 2D measurement of the 3D point public: - ResectioningFactor(const SharedNoiseModel& model, const Symbol& key, - const shared_ptrK& calib, const Point2& p, const Point3& P) : - Base(model, key), K_(calib), P_(P), p_(p) { - } - virtual ~ResectioningFactor() {} + /// Construct factor given known point P and its projection p + ResectioningFactor(const SharedNoiseModel& model, const Key& key, + const shared_ptrK& calib, const Point2& p, const Point3& P) : + Base(model, key), K_(calib), P_(P), p_(p) { + } - ADD_CLONE_NONLINEAR_FACTOR(ResectioningFactor) - - virtual Vector evaluateError(const Pose3& X, boost::optional H = boost::none) const { - SimpleCamera camera(*K_, X); - Point2 reprojectionError(camera.project(P_, H) - p_); - return reprojectionError.vector(); - } + /// evaluate the error + virtual Vector evaluateError(const Pose3& pose, boost::optional H = + boost::none) const { + SimpleCamera camera(*K_, pose); + Point2 reprojectionError(camera.project(P_, H) - p_); + return reprojectionError.vector(); + } }; -/*******************************************************************************/ -/** - * Camera: f = 1.0, Image: 100x100, center: 50.0, 50.0 +/******************************************************************************* + * Camera: f = 1, Image: 100x100, center: 50, 50.0 * Pose (ground truth): (Xw, -Yw, -Zw, [0,0,2.0]') * Known landmarks: * 3D Points: (10,10,0) (-10,10,0) (-10,-10,0) (10,-10,0) * Perfect measurements: * 2D Point: (55,45) (45,45) (45,55) (55,55) - */ + *******************************************************************************/ int main(int argc, char* argv[]) { - /* read camera intrinsic parameters */ - shared_ptrK calib(new Cal3_S2(1.0, 1.0, 0, 50.0, 50.0)); + /* read camera intrinsic parameters */ + shared_ptrK calib(new Cal3_S2(1, 1, 0, 50, 50)); - /* create keys for variables */ - // we have only 1 variable to solve: the camera pose - Symbol X('x',1); + /* 1. create graph */ + NonlinearFactorGraph graph; - /* 1. create graph */ - NonlinearFactorGraph graph; + /* 2. add factors to the graph */ + // add measurement factors + SharedDiagonal measurementNoise = sharedSigmas(Vector_(2, 0.5, 0.5)); + boost::shared_ptr factor; + graph.push_back( + boost::make_shared(measurementNoise, X(1), calib, + Point2(55, 45), Point3(10, 10, 0))); + graph.push_back( + boost::make_shared(measurementNoise, X(1), calib, + Point2(45, 45), Point3(-10, 10, 0))); + graph.push_back( + boost::make_shared(measurementNoise, X(1), calib, + Point2(45, 55), Point3(-10, -10, 0))); + graph.push_back( + boost::make_shared(measurementNoise, X(1), calib, + Point2(55, 55), Point3(10, -10, 0))); - /* 2. add factors to the graph */ - // add measurement factors - SharedDiagonal measurementNoise = sharedSigmas(Vector_(2, 0.5, 0.5)); - boost::shared_ptr factor; - factor = boost::shared_ptr(new ResectioningFactor( - measurementNoise, X, calib, Point2(55.0, 45.0), Point3(10.0, 10.0, 0.0))); - graph.push_back(factor); - factor = boost::shared_ptr(new ResectioningFactor( - measurementNoise, X, calib, Point2(45.0, 45.0), Point3(-10.0, 10.0, 0.0))); - graph.push_back(factor); - factor = boost::shared_ptr(new ResectioningFactor( - measurementNoise, X, calib, Point2(45.0, 55.0), Point3(-10.0, -10.0, 0.0))); - graph.push_back(factor); - factor = boost::shared_ptr(new ResectioningFactor( - measurementNoise, X, calib, Point2(55.0, 55.0), Point3(10.0, -10.0, 0.0))); - graph.push_back(factor); + /* 3. Create an initial estimate for the camera pose */ + Values initial; + initial.insert(X(1), + Pose3(Rot3(1, 0, 0, 0, -1, 0, 0, 0, -1), Point3(0, 0, 2))); - /* 3. Create an initial estimate for the camera pose */ - Values initial; - initial.insert(X, Pose3(Rot3(1.,0.,0., - 0.,-1.,0., - 0.,0.,-1.), Point3(0.,0.,2.0))); + /* 4. Optimize the graph using Levenberg-Marquardt*/ + Values result = LevenbergMarquardtOptimizer(graph, initial).optimize(); + result.print("Final result:\n"); - /* 4. Optimize the graph using Levenberg-Marquardt*/ - Values result = LevenbergMarquardtOptimizer(graph, initial).optimize(); - result.print("Final result: "); - - return 0; + return 0; } diff --git a/examples/Data/calib.txt b/examples/Data/calib.txt deleted file mode 100644 index cb8b77384..000000000 --- a/examples/Data/calib.txt +++ /dev/null @@ -1 +0,0 @@ -800 600 1119.61507797 1119.61507797 399.5 299.5 diff --git a/examples/Data/landmarks.txt b/examples/Data/landmarks.txt deleted file mode 100644 index f6dd9714e..000000000 --- a/examples/Data/landmarks.txt +++ /dev/null @@ -1,9 +0,0 @@ -7 -0 0 0 0 -1 10 0 0 -2 0 10 0 -3 10 10 0 -4 0 0 10 -5 10 0 10 -6 0 10 10 - diff --git a/examples/Data/measurements.txt b/examples/Data/measurements.txt deleted file mode 100644 index ffed3636e..000000000 --- a/examples/Data/measurements.txt +++ /dev/null @@ -1,12 +0,0 @@ -10 -1 ttpy10.feat -2 ttpy20.feat -3 ttpy30.feat -4 ttpy40.feat -5 ttpy50.feat -6 ttpy60.feat -7 ttpy70.feat -8 ttpy80.feat -9 ttpy90.feat -10 ttpy100.feat - diff --git a/examples/Data/poses.txt b/examples/Data/poses.txt deleted file mode 100644 index 72fec9114..000000000 --- a/examples/Data/poses.txt +++ /dev/null @@ -1,12 +0,0 @@ -10 -1 ttpy10.pose -2 ttpy20.pose -3 ttpy30.pose -4 ttpy40.pose -5 ttpy50.pose -6 ttpy60.pose -7 ttpy70.pose -8 ttpy80.pose -9 ttpy90.pose -10 ttpy100.pose - diff --git a/examples/Data/sphere2500.txt b/examples/Data/sphere2500.txt new file mode 100644 index 000000000..dd76a3c8d --- /dev/null +++ b/examples/Data/sphere2500.txt @@ -0,0 +1,4949 @@ +EDGE3 0 1 0.341895 -0.0416997 0.0330394 -0.00305942 0.00822248 0.1802 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1 2 0.229005 0.138346 -0.0985239 -0.00165533 0.0168837 0.111357 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2 3 0.134845 -0.100952 -0.235999 -0.00238046 -0.00487134 0.120841 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 3 4 0.160394 0.0789167 -0.144281 0.00735169 -5.00329e-05 0.153437 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 4 5 0.325826 -0.0659292 -0.0839178 -0.0155927 0.00860976 0.170047 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 5 6 0.204328 -0.0241672 -0.0128254 -0.00899836 0.00684956 0.0630334 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 6 7 0.259333 -0.220076 -0.122115 0.0124792 0.0181515 0.151092 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 7 8 0.330423 -0.218479 0.184829 -0.00315405 0.00835744 0.119863 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 8 9 0.279749 -0.0817312 -0.0311683 0.0129414 0.00155956 0.0807447 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 9 10 0.439651 -0.036304 -0.0979001 -0.0188992 -0.00969819 0.153405 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 10 11 0.448391 0.0194033 -0.0588868 -0.00494734 0.0022853 0.133584 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 11 12 0.601774 -0.00596884 -0.0316864 0.0135014 -0.000518361 0.149296 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 12 13 0.0850905 -0.0358214 0.0945044 0.00108708 -0.00405567 0.0956726 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 13 14 0.406341 -0.0979121 0.0146315 -0.00708947 0.00952537 0.0850412 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 14 15 0.34657 0.120479 -0.0772302 0.011385 -0.0136623 0.132946 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 15 16 0.456464 -0.230793 0.0240143 -0.0126459 0.00734671 0.157528 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 16 17 0.514306 -0.0150626 -0.0145896 -0.00750411 0.00513844 0.227827 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 17 18 0.534286 0.253572 0.100366 -0.00394475 0.02339 0.14888 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 18 19 0.345823 0.105393 0.0308981 0.000962285 0.00837484 0.0281836 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 19 20 0.46807 -0.0543662 0.0352444 -0.00353143 0.0115196 0.0685084 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 20 21 0.569866 0.153941 0.181648 0.00462734 0.0263004 0.0594094 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 21 22 0.48147 -0.165285 -0.024962 0.00338119 0.0215372 0.0682864 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 22 23 0.457005 -0.154486 0.111581 -0.00610449 0.0139356 0.159452 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 23 24 0.460068 0.0012191 -0.000311304 0.0160318 0.0121493 0.154983 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 24 25 0.505705 -0.0457969 0.0571836 0.00455934 0.00520171 0.186015 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 25 26 0.396066 -0.0147835 0.0752318 0.00398689 0.00314298 0.111818 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 26 27 0.554342 -0.082874 0.0195301 -0.000183441 0.0103731 0.143704 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 27 28 0.405677 -0.0164516 -0.14359 0.00905256 0.020269 0.165999 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 28 29 0.366064 0.109363 0.0995936 -0.0117813 0.0132566 0.0900062 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 29 30 0.447825 -0.0626529 -0.073141 0.00491515 0.00257864 0.162262 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 30 31 0.446624 -0.149658 0.0423714 0.00803511 0.0203393 0.146502 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 31 32 0.327353 -0.0599871 0.00611897 0.018532 0.00795743 0.120627 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 32 33 0.709329 -0.188287 0.0378529 -0.0021579 0.0227656 0.167402 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 33 34 0.428707 0.162405 0.00594776 -0.0121099 0.00270696 0.145808 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 34 35 0.356338 0.033284 -0.199599 -0.0140608 0.0128365 0.185326 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 35 36 0.521019 -0.0505509 -0.164282 -0.0129157 0.0206636 0.156898 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 36 37 0.329602 0.0156168 0.0525484 0.00677584 0.0125686 0.198656 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 37 38 0.366813 -0.0752683 -0.115229 0.00276851 0.0200873 0.0678134 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 38 39 0.618377 0.0578938 0.103393 0.0141113 0.00361122 0.13266 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 39 40 0.636906 0.157098 -0.0500064 -0.015852 0.0169927 0.0801991 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 40 41 0.55055 0.0364808 -0.0365541 0.00986673 0.019174 0.0917538 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 41 42 0.660865 0.171451 -0.110704 -0.0094262 0.0176371 0.150958 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 42 43 0.502157 0.166008 -0.0195176 -0.00328711 0.0132678 0.0951723 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 43 44 0.494995 0.0325404 -0.0791926 -0.000984901 0.0261799 0.016442 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 44 45 0.357421 -0.179353 -0.253832 -0.00177872 0.0336155 0.111331 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 45 46 0.549017 -0.0323211 0.0437218 -0.0199969 0.014327 0.0995373 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 46 47 0.59857 -0.0825892 -0.0750772 -0.00203336 0.00684634 0.157466 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 47 48 0.634876 -0.0183952 0.0245626 -0.00470859 0.012947 0.150374 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 48 49 0.542938 -0.115345 0.00522098 0.00766275 0.0289495 0.159793 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 49 50 0.786233 0.0643949 -0.139267 0.00527237 0.0170935 0.178381 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 0 50 0.123684 -3.04765 -0.0287081 0.0530372 -0.0120609 -0.0849653 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 50 51 0.670888 -0.239288 0.144786 0.0122646 0.00233746 0.0980908 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1 51 -0.119112 -3.01805 -0.0691574 0.062941 -0.00919775 -0.0807439 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 51 52 0.988066 -0.119053 0.079414 -0.0073222 0.0152928 0.110527 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2 52 -0.245056 -2.86505 -0.129966 0.0741988 0.00212195 -0.00388232 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 52 53 0.550309 0.112491 -0.159187 -0.00202003 0.0132805 0.0357324 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 3 53 -0.0837652 -3.07691 -0.138081 0.0598365 -0.00661566 -0.00823764 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 53 54 0.638918 0.0661151 0.0442451 0.00714191 0.00528336 0.0763707 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 4 54 -0.0711695 -2.97051 -0.100013 0.0618648 0.0103853 -0.00667934 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 54 55 0.62477 -0.00411993 -0.0479437 0.000918363 0.0215121 0.102648 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 5 55 0.100612 -3.03312 -0.090605 0.0466845 0.00534488 0.0147111 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 55 56 0.765626 -0.0632934 -0.14521 0.00169523 0.0125478 0.123455 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 6 56 0.0371277 -3.07963 -0.176527 0.0621802 0.00868157 -0.0494556 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 56 57 0.780791 0.0445135 0.076528 0.0146365 0.0234281 0.0577835 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 7 57 0.104692 -3.09555 -0.120551 0.0713038 0.000495396 0.0600088 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 57 58 0.677334 0.0523832 -0.129781 0.00652229 0.00917402 0.0769604 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 8 58 0.00719936 -3.14389 -0.027828 0.0624536 0.00342915 -0.0442992 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 58 59 0.770904 0.00617635 -0.0745303 0.00312528 0.0267292 0.122643 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 9 59 0.0926379 -3.00401 -0.0471469 0.0624169 -0.000724871 0.0195497 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 59 60 0.774808 -0.135367 -0.0248524 -0.00390813 0.00350772 0.158576 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 10 60 0.0708412 -3.06927 -0.0337878 0.0617057 0.00304641 -0.013248 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 60 61 0.479333 -0.0126589 -0.102246 0.0136302 0.00491826 0.182465 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 11 61 0.154444 -3.02448 -0.160338 0.0570176 -0.00126667 0.0980274 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 61 62 0.797582 0.0438476 0.0310194 0.00323644 0.0280618 0.149832 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 12 62 0.178067 -3.03583 -0.146661 0.0667198 -0.00346562 -0.0308351 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 62 63 0.742007 0.107876 -0.103637 0.00312823 0.00702323 0.185749 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 13 63 0.113612 -3.13653 0.00541842 0.0425655 0.00547184 0.0944204 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 63 64 0.689769 0.199185 0.0815092 0.00595832 0.0212964 0.191178 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 14 64 -0.191278 -3.10587 -0.315564 0.0792905 -0.0108376 -0.0168051 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 64 65 0.925214 0.170788 -0.0242523 0.000629209 0.00328006 0.094619 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 15 65 -0.0746119 -3.10285 -0.027189 0.0672817 -0.0130186 -0.00728663 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 65 66 0.706086 0.26849 -0.0748405 -0.00176989 0.0120543 0.117096 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 16 66 0.00767487 -2.90585 -0.0636412 0.0677065 -0.00101756 0.0539061 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 66 67 0.638484 -0.0754865 -0.0200711 0.00257019 0.0237712 0.0978569 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 17 67 0.0348257 -3.07488 0.0865152 0.0564331 -0.0325694 -0.0386875 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 67 68 0.856711 0.0944398 0.0924844 0.0176543 0.0199852 0.162469 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 18 68 0.034272 -2.9771 -0.0275615 0.0596048 -0.00746308 -0.022851 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 68 69 0.833231 0.0810845 -0.168993 -0.0104211 0.0256571 0.121276 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 19 69 0.0414539 -2.94622 -0.147426 0.0339762 0.0020352 0.0597721 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 69 70 0.657439 -0.0980627 -0.177485 -0.00599363 0.0139985 0.0703728 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 20 70 -0.0269102 -2.79063 -0.0848862 0.07 0.00218479 -0.022311 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 70 71 0.706164 -0.049235 -0.0823152 0.00304587 0.00223893 0.0819797 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 21 71 -0.0671743 -3.07386 -0.0497795 0.0413955 0.00343211 0.0236128 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 71 72 0.747846 -0.0790405 0.0165401 -0.00427178 -0.0167707 0.161205 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 22 72 -0.0362474 -3.05248 -0.160313 0.0548681 0.00678718 0.0033359 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 72 73 0.920407 -0.0152539 0.117976 0.0108622 0.011454 0.145331 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 23 73 0.119773 -3.09523 -0.13553 0.071927 0.0117753 0.0781413 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 73 74 0.517825 0.0136797 -0.0438358 0.00960028 -0.00581963 0.0677343 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 24 74 0.14435 -2.94311 -0.0670919 0.0550877 0.00814789 0.0152755 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 74 75 0.830853 -0.144022 -0.147814 0.00188492 0.0273945 0.156717 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 25 75 0.0212556 -3.1875 -0.154731 0.0599553 -0.00954908 0.0151185 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 75 76 0.75027 -0.0799915 -0.0511733 -0.00332044 0.024846 0.116136 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 26 76 0.0657844 -3.08702 -0.00356366 0.0551804 0.00618433 0.0365075 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 76 77 0.906628 0.0631322 0.137461 -0.00533686 0.041319 0.134266 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 27 77 -0.0102091 -2.86533 0.139962 0.0316793 0.00190037 -0.0466061 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 77 78 0.727647 -0.028039 0.00313257 -0.0121147 0.0101058 0.0317401 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 28 78 -0.116977 -3.13993 -0.0097921 0.0610097 0.00271574 0.038266 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 78 79 0.732052 -0.0104581 -0.178661 0.00100567 0.0259595 0.130936 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 29 79 -0.0591044 -3.10293 -0.164402 0.0778681 -0.0135122 -0.0160974 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 79 80 0.866 0.115588 -0.170978 0.0205527 0.0208347 0.158125 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 30 80 -0.192369 -3.0277 0.0384235 0.0683819 -0.00885277 -0.0211964 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 80 81 0.918307 0.211437 -0.0455169 0.0101531 0.0110553 0.0215029 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 31 81 -0.0590693 -3.17731 -0.0370921 0.0778469 -8.21782e-05 -0.0427244 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 81 82 0.660276 -0.0939153 0.0456885 -0.0102971 0.0148405 0.148103 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 32 82 0.0104447 -2.95858 -0.123556 0.0650866 0.0103634 -0.0189355 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 82 83 0.808712 0.0158234 0.0759911 0.0163393 0.0257923 0.102308 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 33 83 -0.166851 -3.00612 -0.0390378 0.0577458 0.0108401 -0.0267258 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 83 84 0.977589 -0.0806277 -0.0165069 0.00213041 -0.00959509 0.0372927 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 34 84 -0.0838249 -2.94966 -0.159055 0.0583742 0.0147493 -0.0694411 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 84 85 0.931384 -0.0211719 0.045156 0.00756331 0.0138164 0.0928838 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 35 85 -0.0330709 -3.08556 -0.027849 0.0752036 -0.00987694 -0.0274941 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 85 86 0.847935 0.105966 -0.0790951 0.00428931 0.00828281 0.140235 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 36 86 0.0352295 -3.03801 -0.120413 0.0595869 -0.00147408 -0.0323874 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 86 87 0.816373 -0.0484386 0.0967984 0.00611094 0.0188194 0.11687 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 37 87 0.0288712 -3.21631 0.0677728 0.0650017 0.0149769 0.0713844 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 87 88 1.09479 0.103914 -0.166369 0.00657754 0.0309438 0.13905 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 38 88 -0.0353526 -2.88279 -0.148361 0.075654 0.00102302 0.0378177 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 88 89 0.951079 0.0478632 0.079033 0.000633434 0.0269522 0.148837 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 39 89 -0.00830657 -3.0073 0.00305971 0.0371114 -0.0114751 -0.0340174 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 89 90 0.898548 0.0121024 -0.0233981 -0.00845966 0.0260817 0.0816812 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 40 90 0.0777223 -2.85121 0.0761198 0.0645183 0.011419 0.0371427 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 90 91 0.986115 0.0617607 -0.07348 0.0162668 0.0182121 0.138291 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 41 91 0.021105 -3.00492 -0.133593 0.0660761 -0.00215976 -0.0467747 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 91 92 1.19151 -0.125735 -0.140539 0.0172272 0.0115928 0.115608 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 42 92 -0.089812 -3.01466 -0.287607 0.0613892 -0.00326825 0.0134093 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 92 93 0.969192 0.137519 -0.0466096 -0.00273227 0.0170129 0.0609192 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 43 93 0.130522 -3.11783 -0.311142 0.0435 0.00716509 -0.0287382 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 93 94 0.935602 -0.0420428 -0.278862 0.0049017 0.0236357 0.143001 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 44 94 -0.0979209 -2.95504 -0.0934092 0.0514609 -0.00431777 0.060794 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 94 95 0.933126 0.0691404 -0.0493149 0.013523 0.0221061 0.0887086 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 45 95 -0.0384673 -3.09158 -0.00400611 0.0764242 -0.0122058 -0.00549579 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 95 96 0.980764 0.00375579 -0.101989 -0.0151014 0.0219557 0.179364 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 46 96 0.107757 -2.94807 -0.0544414 0.0615862 0.000351276 -0.0248295 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 96 97 1.12489 -0.0646296 0.0312703 0.0159264 0.0251221 0.166064 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 47 97 0.191799 -2.98088 -0.114885 0.0574689 -0.0206359 0.0206131 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 97 98 0.92336 0.12824 -0.110114 -0.00649851 -0.00482511 0.0686087 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 48 98 -0.114557 -2.90895 -0.336941 0.0632329 0.00908172 0.00472821 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 98 99 0.978164 0.0557018 0.0139987 0.012144 0.0170814 0.0551827 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 49 99 0.0447448 -3.17938 -0.0524665 0.0373712 0.0252483 0.0543531 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 99 100 1.02609 0.0363458 -0.0675104 -0.00120738 0.00734949 0.0963506 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 50 100 0.294107 -2.97696 0.0372275 0.0522773 0.0092289 -0.00933808 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 100 101 1.13013 0.028431 -0.203878 0.0192625 -0.00258903 0.121634 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 51 101 -0.0215351 -3.05915 -0.14967 0.0579652 -0.00267727 0.0292234 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 101 102 0.969271 -0.00770857 0.0840952 0.0192736 0.028709 0.0958533 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 52 102 -0.173278 -3.06042 0.177547 0.062305 0.0012112 0.0126766 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 102 103 1.04189 0.021552 -0.101847 0.00109935 6.5766e-05 0.13003 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 53 103 -0.00268539 -3.08559 -0.202858 0.0525346 0.0105739 -0.0401761 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 103 104 1.03192 0.122897 0.253434 -0.00899381 0.0419305 0.136339 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 54 104 0.0433166 -3.06641 -0.116031 0.046668 -0.0105325 0.0487376 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 104 105 1.08911 0.113631 -0.230208 0.00445056 0.00934039 0.0489845 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 55 105 0.0259222 -2.88869 0.00719153 0.0559624 0.00737045 -0.0210868 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 105 106 1.03026 0.175845 -0.148347 -0.00802826 0.0258392 0.0752439 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 56 106 -0.0785152 -3.13599 -0.180788 0.0626308 0.00787653 -0.0364762 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 106 107 1.02205 0.0709188 -0.0572234 -0.00613664 0.0242141 0.124595 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 57 107 -0.0441094 -2.91311 -0.116708 0.0625226 0.00366493 0.0213254 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 107 108 0.980173 0.0959369 -0.0752456 -0.00338487 0.0191653 0.0715011 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 58 108 0.0230801 -2.97504 -0.357061 0.0670757 -0.00907589 0.0247295 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 108 109 1.05095 -0.0257689 -0.023528 0.00852657 -0.00166744 0.141457 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 59 109 -0.00305562 -3.12308 -0.287325 0.0571011 0.00406724 0.031909 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 109 110 1.20359 -0.0647622 -0.0597841 -0.0088591 0.0106593 0.142081 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 60 110 -0.025776 -2.93824 -0.0518619 0.0586967 -0.00746266 -0.00333775 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 110 111 0.95796 0.131102 -0.0761098 0.00586207 0.0213103 0.0522156 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 61 111 -0.0288368 -3.12871 -0.17189 0.0684542 0.00932534 -0.0442089 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 111 112 1.05014 -0.0223277 -0.233038 -0.00120831 0.0330753 0.180874 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 62 112 -0.129161 -3.26124 -0.190558 0.053319 -0.0129184 -0.0431992 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 112 113 1.11301 -0.131397 -0.0723134 0.00787925 0.021937 0.114543 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 63 113 0.0883249 -3.13239 -0.04713 0.0580108 0.0103668 0.0864995 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 113 114 1.147 -0.0327704 0.0305984 0.0149103 0.0156073 0.0978184 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 64 114 0.0154263 -3.12403 -0.0570956 0.0536973 -0.0147353 0.0828102 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 114 115 1.1207 -0.0117095 -0.223917 -0.00635155 0.0218446 0.195917 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 65 115 0.184162 -3.0453 -0.118383 0.0452144 0.00487106 0.0290297 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 115 116 1.07318 -0.0107915 -0.191525 -0.00909093 0.0330703 0.153907 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 66 116 0.0749906 -3.08305 -0.135897 0.0728186 0.000699285 0.00679558 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 116 117 1.19468 -0.159599 -0.0241275 -0.00377132 0.0304561 0.104646 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 67 117 -0.0305342 -3.10432 0.00537417 0.0588 0.00781384 0.0588515 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 117 118 1.18149 0.0809769 0.0817434 0.0125689 0.0203771 0.0860039 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 68 118 -0.0387159 -3.01347 -0.108519 0.0443164 -0.00294548 -0.012414 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 118 119 1.27252 0.0408358 -0.0858404 -0.00278268 0.0175813 0.118333 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 69 119 -0.0875281 -2.96544 -0.0468108 0.0598179 -0.00805469 0.0347036 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 119 120 1.19134 0.0228141 0.0131211 -0.00107807 0.0364803 0.225035 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 70 120 -0.0501515 -3.09343 -0.0300745 0.0650498 -0.0223053 -0.0662907 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 120 121 1.24715 0.0802271 0.0691544 0.00313991 0.0247522 0.118582 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 71 121 0.00551799 -3.1507 -0.223002 0.070943 -0.0169216 -0.0146807 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 121 122 1.30121 -0.0106717 0.100456 0.0173213 0.00872086 0.0631275 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 72 122 0.0597231 -3.08063 -0.127074 0.068257 -0.0144557 -0.0379985 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 122 123 1.17626 0.120445 0.0833338 0.00792691 0.0209958 0.115622 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 73 123 0.0273583 -3.01523 -0.0374404 0.0724553 -0.00740781 -0.0536889 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 123 124 1.44683 0.08159 0.130293 -0.00790478 0.010436 0.143127 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 74 124 -0.140182 -2.86662 -0.0667824 0.0576166 0.0029843 0.0347212 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 124 125 1.15683 0.0142598 -0.0920316 -0.000941139 0.0175395 0.0916134 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 75 125 0.149265 -3.11637 0.114881 0.0633796 -0.00387822 -0.021386 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 125 126 1.14944 -0.152584 -0.0639707 -0.00797578 0.0142752 0.130386 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 76 126 0.0649766 -3.13012 0.115222 0.0622991 -0.00751953 -0.0528066 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 126 127 1.31421 -0.0301921 0.0136282 0.0260088 0.0234023 0.0419565 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 77 127 -0.0452628 -2.9625 -0.119995 0.0736495 0.00141112 -0.0667184 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 127 128 1.1777 -0.0441652 -0.0328759 0.00563511 0.0284357 0.129802 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 78 128 -0.0235386 -3.20664 -0.00789819 0.0569585 -0.0118202 0.0244622 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 128 129 1.25589 -0.0832053 0.0755096 0.0201099 0.04141 0.0353544 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 79 129 0.0433156 -2.9881 0.0160618 0.0592976 0.00213029 -0.00344917 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 129 130 1.22503 0.0665453 0.0105143 -0.00481882 0.0290614 0.0833613 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 80 130 -0.190593 -3.07302 0.0165346 0.0586789 -0.0121648 0.00239104 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 130 131 1.38719 0.0506626 -0.103822 -0.00259601 0.031707 0.0950021 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 81 131 -0.0259444 -2.8563 -0.0218777 0.0452204 -0.0147614 0.045108 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 131 132 1.14129 0.0525289 0.0422534 -0.00530144 0.0162883 0.18614 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 82 132 -0.103071 -2.91015 -0.16109 0.0636226 0.00560219 -0.0313934 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 132 133 1.36611 0.0933038 0.0101952 0.0117211 0.00470633 0.0384473 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 83 133 -0.0731008 -3.07324 -0.165711 0.0591486 -0.00617429 0.0386802 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 133 134 1.39693 0.0169225 0.0380645 0.00434782 0.0207293 0.168213 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 84 134 -0.107305 -3.25517 0.0327166 0.068988 -0.00667694 0.0180861 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 134 135 1.23352 0.143751 -0.0425504 0.00736683 0.0135378 0.160424 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 85 135 -0.0838882 -3.19586 -0.207621 0.0688347 0.0144063 -0.0207002 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 135 136 1.41106 -0.0532619 -0.0108934 -0.00082031 0.0144103 0.168857 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 86 136 0.0157613 -2.92032 -0.0431684 0.0642352 -0.00618065 0.0184377 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 136 137 1.15381 0.177075 0.0374688 0.0119533 0.0261397 0.127272 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 87 137 0.00197004 -3.03679 0.0128745 0.0554739 -0.0215757 -0.0446642 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 137 138 1.42676 -0.0517682 -0.164318 -0.0025454 0.0328103 0.0494846 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 88 138 -0.12332 -3.08132 -0.0995277 0.0708194 -0.00806477 -0.00861412 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 138 139 1.26672 0.0397922 -0.0564532 0.00656277 0.0363474 0.202066 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 89 139 -0.00275223 -3.19583 -0.0819252 0.053211 -0.00469646 -0.0567531 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 139 140 1.44915 -0.0475323 0.092421 0.00373852 0.0314975 0.121736 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 90 140 0.104303 -3.11898 -0.266343 0.0649362 0.00958872 0.0740299 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 140 141 1.33591 -0.214487 0.010121 0.00626807 0.017005 0.127453 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 91 141 -0.024415 -2.83466 -0.257886 0.0714659 -0.00812374 -0.0244863 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 141 142 1.35222 0.0658626 0.0313342 -0.00698821 0.0398324 0.129372 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 92 142 -0.0307797 -2.98277 0.074437 0.0607682 -0.0276133 0.0376202 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 142 143 1.48539 0.0659756 0.0937671 0.019014 0.0325928 0.109309 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 93 143 -0.0211845 -3.16763 -0.127323 0.073686 -0.0126257 0.0229932 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 143 144 1.47044 -0.0991464 -0.018496 0.0127829 0.0364172 0.0830905 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 94 144 0.108172 -3.12806 -0.223934 0.0594942 -0.000423085 -0.0965125 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 144 145 1.45225 -0.0303321 0.0124329 -0.00337534 0.0361522 0.176161 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 95 145 0.0559591 -2.82278 -0.0672094 0.0623157 0.00409275 0.000815069 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 145 146 1.39071 -0.210258 -0.0390088 0.00971164 0.0238097 0.163629 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 96 146 0.000928069 -3.04331 0.00953992 0.0516296 -0.0059651 0.0733197 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 146 147 1.57347 0.0979423 0.0218775 -0.00357969 0.0192539 0.213089 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 97 147 0.0309534 -2.97941 -0.114619 0.0555605 0.0175574 -0.0188221 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 147 148 1.27099 -0.0250882 0.0109643 0.0143423 0.0321854 0.154002 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 98 148 -0.193633 -3.07722 -0.0303492 0.0739744 -0.0113989 -0.00917065 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 148 149 1.40051 0.10627 -0.101023 0.00968476 0.0286493 0.140976 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 99 149 -0.0268638 -3.02365 -0.11236 0.0816159 -0.00328121 0.0173223 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 149 150 1.53584 0.259858 -0.067094 0.00836184 0.0232924 0.181033 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 100 150 -0.091195 -3.10917 -0.131026 0.0582938 0.00552301 -0.0772711 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 150 151 1.50343 0.0900941 -0.0232025 -0.00333805 0.0340989 0.121424 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 101 151 -0.184789 -3.14272 -0.235034 0.0588545 -0.00470093 0.0879531 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 151 152 1.54611 0.27024 -0.0573247 0.00315426 0.0491033 0.0892431 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 102 152 -0.0763466 -3.00259 -0.111874 0.0798404 -0.0149104 0.0211824 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 152 153 1.40938 -0.0190962 0.0406198 0.0074728 0.0221496 0.0478455 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 103 153 0.0438277 -2.96722 0.0459768 0.0666088 0.00244816 0.0292068 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 153 154 1.40071 -0.0348716 0.0796097 0.0191604 0.0397561 0.104492 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 104 154 -0.0624419 -3.03437 -0.157666 0.0475526 -0.00097643 0.0339232 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 154 155 1.37532 0.0303392 0.00973663 0.00341224 0.0323813 0.0992893 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 105 155 0.117743 -2.83783 -0.167352 0.0623962 -0.00793055 -0.000516027 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 155 156 1.22703 0.0210456 -0.0498942 0.014615 0.0325815 0.11638 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 106 156 0.0449871 -3.06183 -0.169848 0.0665598 -0.00462507 -0.0692146 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 156 157 1.31766 -0.118396 -0.0643189 0.00910642 0.0185014 0.0524095 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 107 157 -0.0960327 -3.08018 -0.160623 0.0653476 -0.00869054 -0.017762 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 157 158 1.4538 0.111238 0.022365 0.00772061 0.0409316 0.170237 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 108 158 0.104944 -3.01454 -0.0810527 0.0558659 0.000301541 0.0165061 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 158 159 1.47945 0.0548181 -0.117826 -0.00222687 0.0358195 0.165498 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 109 159 0.019539 -2.96727 -0.106413 0.0564583 -0.000718725 0.0118056 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 159 160 1.38283 0.0324891 0.255533 0.0110349 0.0325244 0.12145 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 110 160 -0.00660569 -3.09514 -0.054324 0.0658628 -0.00299355 0.0832041 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 160 161 1.39937 0.0949158 0.03063 0.00995492 0.0392517 0.128412 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 111 161 -0.175793 -3.09713 -0.0226281 0.0514343 -0.00820071 -0.0265973 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 161 162 1.32635 0.00237235 -0.158713 -0.00312757 0.0324963 0.0821186 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 112 162 0.0302867 -2.89947 0.0285285 0.06533 0.000808399 -0.0229159 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 162 163 1.43595 -0.0666765 -0.0226963 0.00287416 0.0456007 0.199184 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 113 163 -0.0432065 -3.1782 -0.150945 0.0711739 -0.0125488 0.084453 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 163 164 1.37631 0.125108 0.101829 0.020338 0.0304776 0.0919236 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 114 164 -0.00322512 -3.02308 0.0908843 0.0864855 0.00608706 -0.0108954 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 164 165 1.47347 -0.0114871 0.0244473 0.00279986 0.0295578 0.104601 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 115 165 0.0180775 -3.05186 -0.186293 0.068491 -0.0050778 -0.0416453 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 165 166 1.39015 -0.0627038 -0.100217 0.00289206 0.0333439 0.0864933 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 116 166 -0.0975132 -3.20295 -0.17434 0.0605142 0.00171958 0.0192081 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 166 167 1.42634 -0.0434544 -0.0641663 -0.00552483 0.0171293 0.093275 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 117 167 0.0654124 -2.96418 -0.217887 0.0633597 -0.00646462 0.0204986 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 167 168 1.46179 -0.000134202 -0.235566 -0.00136664 0.0190626 0.148571 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 118 168 0.100361 -3.04344 -0.158514 0.0432215 0.0123417 -0.00337237 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 168 169 1.50116 -0.0630477 0.110722 0.000250842 0.0448257 0.133308 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 119 169 0.180965 -3.16839 0.0125299 0.0731425 0.000851626 -0.0517885 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 169 170 1.56377 0.144771 0.103893 -0.00860669 0.0354396 0.0886395 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 120 170 0.0746068 -3.01461 -0.18407 0.0589369 -0.0178595 -0.00795362 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 170 171 1.5639 0.00334451 -0.0976223 -0.0049772 0.0323328 0.100328 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 121 171 0.0109993 -3.01379 -0.102388 0.0573484 0.0022302 0.0182129 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 171 172 1.68862 -0.0586818 -0.0303397 -0.00806027 0.0326367 0.0838935 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 122 172 -0.111558 -2.94293 -0.195782 0.0681368 -0.000829466 -0.0214527 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 172 173 1.58131 0.00755403 -0.0452305 0.00340913 0.019952 0.147633 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 123 173 0.0800822 -3.3112 -0.124141 0.0680485 -0.00713025 -0.0775001 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 173 174 1.72212 0.0594114 -0.167495 0.00341528 0.0368757 0.143856 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 124 174 -0.0792538 -3.01441 0.00500951 0.0601768 0.00993413 -0.0598378 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 174 175 1.59936 -0.0663353 0.0552965 0.00100654 0.0136019 0.144131 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 125 175 0.0662933 -2.99194 -0.286008 0.0782552 -0.0101059 0.0277765 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 175 176 1.72026 0.0330118 -0.0506746 0.0101457 0.0330823 0.166277 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 126 176 -0.0173762 -3.1868 -0.0394693 0.0597979 0.00592918 -0.0261937 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 176 177 1.60182 0.0883911 0.132384 0.00968364 0.0338752 0.0774389 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 127 177 -0.0569387 -2.96806 -0.200005 0.0443698 0.013978 0.0326017 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 177 178 1.692 0.0275745 0.0436645 -0.008861 0.0166822 0.172091 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 128 178 -0.0739367 -3.07313 -0.0364267 0.0708591 -0.026773 0.0548767 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 178 179 1.4636 0.277218 0.00306782 0.00246004 0.0290051 0.121671 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 129 179 0.0334896 -3.08379 -0.165323 0.057635 0.0059853 0.0459455 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 179 180 1.85634 -0.0585747 0.0483485 0.0141806 0.0294442 0.179783 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 130 180 0.0600659 -3.04662 -0.232627 0.0534284 -0.000797089 0.00862149 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 180 181 1.64267 -0.0179925 0.00251776 0.00863421 0.0417442 0.0998906 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 131 181 -0.0705189 -3.08063 -0.0281943 0.0510869 0.0133379 0.0199902 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 181 182 1.80108 0.00341645 0.1077 -0.00103219 0.033739 0.0928288 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 132 182 0.137935 -3.01711 -0.24742 0.063955 -0.0153704 -0.0151215 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 182 183 1.68527 0.061889 -0.183727 0.00135907 0.0340176 0.145758 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 133 183 0.113449 -3.24191 -0.0118171 0.0583434 0.0133421 0.0758862 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 183 184 1.51155 0.149797 0.0264479 -0.00738633 0.0406307 0.101637 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 134 184 -0.00249721 -3.08846 -0.119883 0.0578308 -0.00454597 -0.00656585 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 184 185 1.68482 0.0347309 -0.0284604 0.00380256 0.0478564 0.109049 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 135 185 0.00297203 -3.10605 0.158867 0.0726803 0.00413905 -0.0172719 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 185 186 1.76482 -0.0323671 0.069191 0.00190559 0.022595 0.175645 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 136 186 0.0484651 -2.93186 -0.241964 0.0607642 -0.000809346 -0.0574341 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 186 187 1.50619 0.2211 -0.0934862 0.0213632 0.038668 0.144495 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 137 187 0.0697683 -3.12328 -0.185728 0.081538 -0.000836861 -0.070255 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 187 188 1.77122 -0.15748 0.0888511 0.0125665 0.0469711 0.0232227 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 138 188 -0.182655 -3.20378 -0.147575 0.0469276 0.00145833 -0.0471949 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 188 189 1.59992 0.0430631 -0.0982293 0.00496286 0.0396087 0.101366 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 139 189 -0.0892435 -2.88768 -0.0776466 0.0541292 0.00431353 -0.0701898 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 189 190 1.77684 -0.12741 -0.065838 0.00588863 0.0356693 0.0745784 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 140 190 -0.0090601 -3.01519 -0.0517473 0.0579129 -0.0073762 0.120663 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 190 191 1.81203 0.0301962 0.0214748 -0.00284979 0.0326308 0.0810004 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 141 191 0.00510901 -2.98367 -0.207731 0.0618182 -0.013076 -0.00249131 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 191 192 1.72204 -0.00873939 -0.125301 -0.00194083 0.027942 0.123151 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 142 192 0.0666604 -2.89114 -0.0680906 0.062445 0.00488451 0.0292928 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 192 193 1.62744 0.000274444 0.135329 0.0139251 0.0362447 0.0973624 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 143 193 -0.022781 -3.08216 -0.0800965 0.0701637 -0.00246595 -0.0643767 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 193 194 1.82308 0.0310364 0.155292 -0.000520669 0.045176 0.0986018 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 144 194 0.00638825 -3.00042 -0.151838 0.0498274 -0.00580071 0.0144146 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 194 195 1.5502 0.0689414 -0.120656 0.0216901 0.0413976 0.140854 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 145 195 0.0368719 -2.91428 -0.0857056 0.0586239 -0.000996116 0.0439876 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 195 196 1.78057 0.146144 0.0610981 -0.0104951 0.0417118 0.0880281 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 146 196 -0.0114202 -3.19583 -0.309015 0.0606655 0.00342527 0.0297961 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 196 197 1.65409 -0.196292 0.0459151 0.00268357 0.019473 0.101011 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 147 197 -0.00871662 -3.01961 -0.137155 0.0507975 0.00196904 -0.0465022 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 197 198 1.69503 0.195056 -0.169086 0.0124826 0.0199831 0.110915 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 148 198 -0.0677675 -2.98079 -0.0382307 0.0585965 -0.00817753 0.111116 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 198 199 1.76688 0.097001 -0.0593896 0.00970437 0.0438005 0.156703 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 149 199 0.0191126 -3.02994 -0.129049 0.0661753 -0.0107078 -0.0667044 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 199 200 1.90254 0.325562 -0.0777571 -0.00630681 0.0371526 0.0846623 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 150 200 0.0382134 -3.05662 -0.135943 0.0639997 0.0117655 -0.000529756 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 200 201 1.68051 -0.033179 -0.0389823 0.00465261 0.0285638 0.144896 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 151 201 0.0731876 -3.11192 -0.196398 0.0713868 0.00265962 -0.0227748 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 201 202 1.86513 0.254449 0.00888724 0.0247806 0.044651 0.176677 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 152 202 0.130243 -3.0951 -0.054181 0.0575143 -0.0119977 0.0214721 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 202 203 1.82231 -0.109072 -0.163625 0.000832615 0.0403943 0.19324 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 153 203 0.0630173 -2.91525 0.0364883 0.0720316 -0.00919023 -0.00282688 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 203 204 1.92344 0.0251315 0.120875 0.00792463 0.0475588 0.0693731 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 154 204 0.161642 -3.15779 0.00582814 0.0567933 0.00481272 0.0254752 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 204 205 1.62506 0.111677 -0.0497328 0.00150407 0.0363835 0.14885 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 155 205 -0.0757689 -3.06476 -0.0242418 0.0620182 0.00852524 -0.0957239 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 205 206 1.96882 0.0238452 0.0993766 0.0173079 0.0231871 0.11098 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 156 206 0.102407 -3.05569 -0.172852 0.0768964 0.0127887 -0.011598 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 206 207 2.00298 0.01153 -0.045501 0.00967042 0.0356864 0.117864 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 157 207 -0.0809565 -3.10199 0.0555457 0.0529998 0.0146578 0.0412121 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 207 208 1.66844 0.0318303 -0.13248 0.00210799 0.0507095 0.153367 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 158 208 0.102104 -3.09037 -0.0644268 0.0546204 0.00778132 -0.0176055 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 208 209 1.78938 0.194344 0.0187949 0.0120475 0.0205472 0.0718317 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 159 209 -0.0346452 -3.11184 -0.0606164 0.0479362 -0.00520853 0.0396631 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 209 210 1.75655 -0.145987 -0.138479 0.00822308 0.0312839 0.147412 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 160 210 0.0286888 -2.96378 -0.17248 0.0364285 0.00383676 -0.112886 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 210 211 1.74459 -0.0573695 -0.00494877 0.00746975 0.034189 0.146847 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 161 211 -0.142765 -3.17487 -0.190226 0.0360753 -0.00268244 -0.0282957 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 211 212 1.83911 0.0396383 0.138066 0.000450027 0.0316329 0.0797656 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 162 212 -0.0016887 -3.03451 -0.0732073 0.0533917 0.00219507 -0.0102065 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 212 213 2.02525 0.0376045 -0.121723 0.00198343 0.0433563 0.118119 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 163 213 0.0686502 -2.99854 -0.033735 0.0487614 -0.0172263 0.0117656 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 213 214 1.8112 0.014488 0.0610334 0.0120029 0.03957 0.0178461 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 164 214 0.00559263 -3.04826 0.110138 0.0777598 -0.00437256 0.0252081 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 214 215 1.92421 0.0628544 -0.0421914 0.0202207 0.030154 0.166039 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 165 215 -0.079513 -2.93213 -0.228321 0.0642961 0.00276748 -0.0160108 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 215 216 1.85809 0.12447 -0.126272 -0.00750494 0.0511746 0.146717 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 166 216 0.000612582 -3.13253 -0.0272573 0.0653026 -0.00817894 -0.0157567 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 216 217 1.92819 0.131562 -0.0262865 -0.0176944 0.0477917 0.108702 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 167 217 0.0263059 -2.91893 -0.272428 0.0582499 0.0179859 -0.0208515 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 217 218 2.09045 0.0502047 0.00895368 0.011666 0.0311209 0.16451 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 168 218 -0.0999359 -2.98392 -0.0647397 0.0654386 0.00280013 -0.0144617 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 218 219 1.66963 -0.0146119 0.0298604 0.00176515 0.0319432 0.171465 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 169 219 0.106994 -3.21091 -0.297587 0.0450544 -0.00822723 0.00345636 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 219 220 1.94352 0.0237944 -0.0206842 -0.00532697 0.0384581 0.132339 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 170 220 0.0292042 -3.14077 -0.131728 0.0489925 0.00504376 0.00583801 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 220 221 2.08627 0.0695488 -0.0603994 0.006781 0.0221916 0.123998 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 171 221 0.0251717 -3.00265 0.0194363 0.070476 -0.0231494 0.00647591 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 221 222 1.74306 0.123654 0.00155131 -0.0147609 0.0406629 0.165205 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 172 222 -0.134656 -3.05362 0.13276 0.06591 -0.0096463 -0.00436685 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 222 223 1.85398 0.259788 0.0394136 0.00485837 0.0331025 0.0911351 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 173 223 -0.062719 -3.15837 -0.0502821 0.0653893 -0.00820904 0.0454966 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 223 224 1.93641 0.262807 0.0398305 0.0108066 0.0295743 0.189469 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 174 224 0.163986 -3.13471 -0.0134047 0.0715719 -0.00539493 0.00133295 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 224 225 1.73706 -0.0894922 -0.214004 -0.00848344 0.0427249 0.207368 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 175 225 0.0106959 -3.0434 -0.204951 0.0740667 -0.00174896 0.0280807 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 225 226 1.95821 0.0290485 -0.00119628 0.00483109 0.0404749 0.106243 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 176 226 0.0531572 -3.02179 -0.167399 0.0532579 0.0120966 -0.000209975 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 226 227 2.05299 0.0827588 -0.0318831 -0.00520823 0.0498765 0.129382 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 177 227 0.0213529 -3.26506 0.031713 0.0584324 0.0142313 -0.0478921 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 227 228 2.07201 0.0649026 -0.00477684 0.001229 0.031251 0.105419 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 178 228 -0.0484436 -3.11359 -0.154497 0.0631709 0.00976347 -0.114208 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 228 229 1.95294 0.039408 -0.0464725 0.00167196 0.0409431 0.131136 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 179 229 -0.00643492 -3.05845 -0.118459 0.0613074 0.00773031 0.0342483 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 229 230 2.03641 0.0722071 -0.0815322 -0.000493797 0.044832 0.131649 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 180 230 0.115083 -2.96394 -0.0422853 0.0540187 0.0032323 0.0455786 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 230 231 1.8818 -0.11954 -0.0325278 0.00161878 0.0286758 0.109708 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 181 231 -0.0168854 -3.08755 -0.309933 0.0605794 -0.00810053 0.0060085 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 231 232 2.14098 -0.168831 0.0265906 -0.0150479 0.0263096 0.106862 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 182 232 0.147606 -3.0981 -0.0701534 0.0699415 -0.000295278 0.0688972 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 232 233 1.83433 0.0734373 0.0660469 -0.00903129 0.0494465 0.121396 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 183 233 -0.00321555 -3.05285 0.0449213 0.0591974 -0.00976622 -0.0415753 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 233 234 1.88659 0.110046 -0.107002 0.000349286 0.0477397 0.127259 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 184 234 -0.0602762 -3.06792 -0.163193 0.079075 -0.00470511 -0.0390876 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 234 235 2.26289 0.0870066 0.000505862 -0.00299947 0.0544787 0.0840462 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 185 235 -0.161752 -3.10469 -0.1211 0.0624799 0.016216 0.0029447 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 235 236 1.98665 -0.0129186 0.00442581 0.00839079 0.0560474 0.159022 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 186 236 0.0346363 -2.96773 -0.0157169 0.0833375 -0.00214156 -0.00922428 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 236 237 1.91157 0.183219 -0.0222053 0.00457593 0.0308936 0.0621001 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 187 237 0.165213 -2.99257 0.00310385 0.0803587 -0.00341481 -0.0300767 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 237 238 2.09429 -0.00379929 -0.134306 0.00880035 0.0410323 0.180148 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 188 238 0.0185541 -3.0517 -0.103473 0.0730379 -0.0124127 -0.0223637 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 238 239 1.77477 -0.0360535 -0.0690612 0.00785704 0.0328021 0.169314 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 189 239 -0.0267558 -3.0413 -0.0526275 0.0711473 0.0155586 0.0168998 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 239 240 2.27011 0.219717 -0.00370011 -0.00356763 0.0603441 0.0819961 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 190 240 0.0767567 -3.03596 -0.000666132 0.0651999 0.00572908 -0.0268885 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 240 241 1.86571 -0.115437 0.00537699 0.0017837 0.0369354 0.0448219 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 191 241 -0.246869 -3.09503 -0.0705801 0.0608872 -0.0132719 0.0295155 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 241 242 1.93868 0.0763127 -0.101444 -0.0013484 0.0343296 0.0914025 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 192 242 -0.0467043 -3.0884 -0.213095 0.0510451 0.0143328 -0.00912357 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 242 243 2.08485 0.0765796 0.0597433 -0.00491673 0.0435209 0.162546 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 193 243 -0.126682 -2.94999 -0.20823 0.0586476 -0.000688903 0.00177961 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 243 244 2.24831 -0.0292934 0.0381868 0.0111353 0.0450596 0.161896 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 194 244 -0.102618 -3.06055 -0.105585 0.0609778 0.00808177 0.0350429 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 244 245 2.12642 -0.0938462 -0.262251 0.00400024 0.0343815 0.0669298 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 195 245 -0.152002 -3.17768 -0.0386919 0.0732517 0.0102084 -0.0124038 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 245 246 2.25275 -0.068501 -0.164155 0.00637231 0.0627578 0.0814566 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 196 246 -0.234046 -3.08278 -0.442751 0.0522283 -0.000301327 -0.00317474 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 246 247 2.02421 0.208041 0.0553142 0.0219963 0.0309713 0.232485 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 197 247 0.137088 -2.90179 -0.283476 0.0563091 -0.00532127 -0.0126661 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 247 248 2.25098 0.199637 0.10075 0.00813927 0.0473805 0.16878 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 198 248 -0.167221 -3.21719 -0.0115691 0.0578296 0.00322409 -0.038098 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 248 249 2.10342 0.107357 -0.15673 0.00997207 0.0528462 0.133786 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 199 249 0.110486 -3.16289 -0.0433531 0.0726547 0.00959121 0.0346844 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 249 250 2.19817 0.218015 -0.00786808 0.0129408 0.0307759 0.154194 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 200 250 -0.0717296 -3.07548 0.0211213 0.0627264 -0.0055114 -0.0103608 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 250 251 2.31288 -0.052153 -0.0731027 -0.00719742 0.0400024 0.116925 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 201 251 -0.00681805 -3.17906 -0.346013 0.054638 0.00747675 -0.0134403 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 251 252 2.18756 -0.0633361 -0.118089 0.00495692 0.052449 0.115732 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 202 252 0.0431136 -3.00939 -0.0155636 0.0716749 -0.00317407 -0.0400628 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 252 253 2.08733 0.05078 -0.0744808 0.00736145 0.0274147 0.0869374 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 203 253 0.131396 -2.95578 -0.00510312 0.0657131 0.0257113 0.028103 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 253 254 2.09822 0.190315 -0.18488 0.000465939 0.0490045 0.138205 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 204 254 0.0838311 -3.06117 -0.143531 0.0593527 -0.0067121 -0.0382022 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 254 255 2.07268 0.043896 0.0290046 0.0137189 0.0463347 0.104311 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 205 255 -0.000913512 -3.09839 -0.126894 0.0531193 -0.000258623 0.0253931 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 255 256 2.03781 -0.05167 0.123522 0.013832 0.0346036 0.0916014 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 206 256 -0.0419883 -3.08009 0.02822 0.0508768 -0.00188593 -0.0164474 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 256 257 2.45744 0.148313 -0.109088 -0.00411675 0.0396744 0.147067 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 207 257 -0.0163456 -3.02109 -0.162527 0.055254 0.0189569 -0.0301234 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 257 258 2.3833 -0.00345305 -0.128278 -0.00581145 0.0395637 0.0883512 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 208 258 0.0830395 -3.17885 0.0327568 0.0467335 -0.0225947 -0.0348089 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 258 259 2.20419 0.199405 -0.00605771 -0.00420014 0.0416097 0.112066 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 209 259 0.0667935 -2.96176 -0.0639898 0.0689552 -0.00737743 0.0511222 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 259 260 2.29002 0.135432 0.0287787 -0.0027658 0.0451641 0.0831062 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 210 260 0.0305222 -3.08883 -0.141418 0.0645893 -0.00811835 -0.012858 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 260 261 2.15078 -0.00596316 -0.135764 0.000299779 0.037295 0.193327 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 211 261 -0.110706 -3.09079 -0.00819562 0.0549579 0.00219491 2.57521e-05 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 261 262 2.20337 0.0580157 0.00134658 0.00386203 0.0501052 0.165391 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 212 262 -0.102122 -3.00302 -0.0615906 0.0609671 -0.0102547 -0.0317258 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 262 263 2.03672 0.197414 -0.19402 0.0269777 0.0520744 0.143433 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 213 263 -0.179033 -3.1427 -0.0505253 0.071954 -0.0128928 0.0568992 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 263 264 2.1035 0.124143 0.0255684 0.015117 0.0505631 0.110192 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 214 264 0.0658537 -3.04313 0.0580409 0.0587429 0.000650224 -0.00385978 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 264 265 2.30918 -0.100238 -0.145686 0.0075786 0.0251499 0.106305 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 215 265 -0.143185 -3.06723 -0.314008 0.0527471 0.00543168 -0.0116116 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 265 266 2.21367 0.0949277 -0.155361 -0.00334258 0.038799 0.149246 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 216 266 -0.0101691 -3.01743 -0.195877 0.0742527 0.00104353 -0.0868762 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 266 267 2.13462 -0.146741 0.0671172 -0.00667222 0.0416776 0.128528 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 217 267 -0.00330242 -3.002 -0.109077 0.0678437 0.010472 0.00506311 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 267 268 2.41615 0.05162 0.0750816 -0.00952927 0.0426124 0.16367 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 218 268 -0.218145 -3.15421 -0.0598618 0.0722774 0.00925724 -0.0436768 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 268 269 2.23469 0.0453752 -0.145289 0.0205 0.0341337 0.128676 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 219 269 -0.0605602 -2.83477 0.0536274 0.0716696 0.00541583 -0.0430848 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 269 270 2.02699 0.121645 0.051122 0.00116677 0.0201445 0.149441 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 220 270 0.0970233 -3.10062 -0.0246899 0.0600018 -0.0140873 -0.0143543 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 270 271 2.27153 0.199102 0.161268 0.0111928 0.0504626 0.0939937 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 221 271 0.0456638 -2.9805 -0.0302129 0.0665857 -0.00501504 -0.0111736 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 271 272 2.18299 -0.107375 0.0409429 0.013585 0.0395822 0.138031 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 222 272 0.148506 -3.07901 -0.218243 0.0753982 0.00574885 0.0366255 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 272 273 2.24056 0.080279 0.130438 0.0105625 0.0342771 0.182198 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 223 273 -0.0556997 -3.18523 -0.235704 0.077776 -0.00873111 0.0409011 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 273 274 2.4215 0.195034 -0.155046 0.00803924 0.0567937 0.139719 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 224 274 -0.0250337 -3.14967 -0.163133 0.0499743 -0.00438829 0.0577658 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 274 275 2.17327 0.134645 0.0613398 -0.00125863 0.0484273 0.0687721 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 225 275 -0.127119 -2.98858 -0.00343526 0.0670647 0.0100908 -0.0347278 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 275 276 2.35378 -0.0715283 -0.0653343 0.0136437 0.0546804 0.122561 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 226 276 0.229636 -3.10875 -0.0812266 0.0574506 0.0125476 0.0860414 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 276 277 1.96311 0.155108 -0.0384223 -0.021755 0.0444909 0.0821412 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 227 277 -0.0786455 -3.13901 -0.0697428 0.0534407 0.018922 -0.0118873 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 277 278 2.27018 0.14436 -0.136726 -0.00354742 0.0421929 0.150762 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 228 278 0.144844 -3.10515 -0.272418 0.0473179 -0.0108012 -0.0179344 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 278 279 2.34324 0.0231502 -0.114825 0.000656235 0.0499106 0.148202 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 229 279 0.135237 -3.10469 0.106597 0.0789428 -0.0188134 0.0214502 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 279 280 2.16599 0.0295354 -0.0855455 0.00969605 0.0411425 0.101733 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 230 280 -0.027205 -3.18812 -0.0374326 0.0701757 0.00788794 -0.00326006 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 280 281 2.25687 0.158581 0.223971 0.0117773 0.0338342 0.142574 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 231 281 0.116528 -3.07257 -0.205221 0.0678889 -0.03243 0.0331513 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 281 282 2.46519 0.125342 -0.083333 -0.00302696 0.0355066 0.0924926 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 232 282 0.102083 -3.10287 -0.150421 0.0469525 -0.0027142 -0.0280216 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 282 283 2.47559 0.0556753 0.219299 0.000645852 0.0396109 0.150877 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 233 283 0.0656143 -3.1271 -0.00171123 0.0801474 0.00726626 0.0179317 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 283 284 2.39062 0.0988383 -0.0962819 -0.0120396 0.0622843 0.107813 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 234 284 -0.000547869 -3.10502 -0.171998 0.0541426 0.0049636 -0.0116743 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 284 285 2.35824 -0.0287721 -0.145039 0.01653 0.0438322 0.161942 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 235 285 -0.0816881 -2.81858 -0.172729 0.0743499 -0.00842549 -0.0485102 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 285 286 2.42832 0.0930126 -0.0489046 0.0106349 0.0476784 0.0673158 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 236 286 0.0484962 -3.03673 -0.273522 0.0629573 -0.00090137 -0.0453009 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 286 287 2.44284 0.0404911 -0.136321 0.026261 0.0466477 0.0555865 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 237 287 -0.032727 -3.13576 -0.16107 0.0573894 -0.0123586 0.0611874 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 287 288 2.41488 0.00870183 -0.20671 -0.00720146 0.0461846 0.122732 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 238 288 -0.0496857 -3.07509 -0.251657 0.0688863 -0.00133531 -0.0200851 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 288 289 2.28864 -0.0381635 -0.0898246 -0.00293641 0.0640621 0.0676576 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 239 289 0.0193968 -2.92723 -0.142801 0.0680957 0.000437974 0.0448117 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 289 290 2.4637 0.0262221 -0.242672 0.0173369 0.0409467 0.0860674 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 240 290 -0.0211913 -2.98593 -0.0887671 0.0585756 -0.0164923 -0.0339397 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 290 291 2.28355 -0.0154505 -0.0915172 -0.00477286 0.0422064 0.0813018 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 241 291 0.086062 -3.04769 -0.116784 0.0708585 0.0146636 -0.0392523 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 291 292 2.58915 0.0339442 -0.0232328 -0.00322147 0.0374201 0.096972 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 242 292 0.00631038 -3.09328 0.107673 0.0559532 0.004636 0.0277906 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 292 293 2.42997 0.0755426 -0.0699184 -0.00669618 0.0435254 0.102059 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 243 293 -0.0706993 -3.09109 -0.0811525 0.0697684 0.00246776 0.0193687 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 293 294 2.49862 0.00910517 0.00335106 0.0157926 0.0401925 0.130325 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 244 294 -0.0228583 -3.2339 -0.0736715 0.045959 5.7608e-05 -0.0290403 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 294 295 2.31422 0.0562027 -0.246499 -0.00411792 0.055953 0.0661303 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 245 295 0.133367 -3.07528 -0.259682 0.0566562 0.0194897 0.0301528 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 295 296 2.46919 0.0840357 -0.067019 0.0167165 0.0550077 0.0923467 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 246 296 -0.0569526 -2.8712 -0.0547276 0.0729565 -0.00132937 0.0161054 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 296 297 2.46877 0.0685008 -0.176631 0.00230117 0.0498114 0.162736 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 247 297 0.0586638 -2.97212 -0.0881569 0.0512024 0.00992174 0.0853792 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 297 298 2.49273 0.0234559 -0.0633944 0.0136503 0.0600681 0.153273 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 248 298 0.175276 -3.06391 0.226309 0.0759751 0.00671959 0.12724 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 298 299 2.44053 0.135077 0.0680864 0.00664862 0.0449906 0.12216 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 249 299 -0.0558853 -3.02436 -0.136848 0.0698958 0.00686718 0.0254077 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 299 300 2.75217 0.0228351 -0.220441 0.0015072 0.0417684 0.0754465 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 250 300 -0.133213 -3.12674 -0.0957537 0.0724965 -0.00742683 -0.011595 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 300 301 2.4764 0.12383 -0.0145078 0.0112092 0.0532307 0.0698002 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 251 301 -0.0651135 -3.03122 -0.170269 0.0683717 0.00515989 0.0554553 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 301 302 2.5853 0.0742644 -0.153793 0.00304487 0.0464858 0.157709 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 252 302 -0.0288678 -3.09016 -0.0523891 0.0510187 -0.00374584 -0.0376563 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 302 303 2.48018 0.167181 -0.0769526 -0.00644395 0.0620504 0.13335 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 253 303 -0.144662 -3.20284 -0.133085 0.0801223 -0.00115644 -0.0253926 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 303 304 2.43786 0.0831799 -0.240887 0.008843 0.0571093 0.194069 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 254 304 -0.0576414 -2.97553 0.0633291 0.062827 0.00159969 -0.0273465 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 304 305 2.6149 -0.0417122 -0.00826959 -0.00122509 0.0348447 0.179542 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 255 305 0.204381 -3.09634 -0.21618 0.0807465 -0.00262199 -0.028427 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 305 306 2.65096 -0.0204622 -0.203166 0.00557884 0.0560473 0.103369 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 256 306 -0.0455904 -3.09673 -0.0862219 0.0549526 0.0193621 0.0184641 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 306 307 2.59701 0.0913949 -0.110267 -0.0172836 0.0417482 0.130464 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 257 307 -0.0810938 -3.07172 0.0394254 0.0754092 -0.000272243 0.00175795 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 307 308 2.6107 0.171221 -0.172001 0.0169908 0.0467304 0.0793681 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 258 308 -0.038977 -2.98935 -0.041741 0.0518484 0.00350401 0.0563979 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 308 309 2.58052 0.156052 -0.0282611 0.026831 0.0615415 0.103556 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 259 309 0.117742 -3.02558 -0.291466 0.0690481 -0.016789 0.0141453 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 309 310 2.54353 0.161132 -0.101395 0.0055641 0.05408 0.148084 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 260 310 0.0983486 -3.04401 0.0630866 0.0647968 0.00689383 0.0215674 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 310 311 2.52355 -0.0753586 -0.0144411 0.00808827 0.0647891 0.0419549 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 261 311 0.103972 -3.23229 -0.132702 0.0606288 -0.00911027 -0.0407024 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 311 312 2.55843 0.191971 -0.117608 0.0192683 0.0332596 0.0574377 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 262 312 -0.146462 -3.2258 -0.024178 0.0555791 -0.00128182 -0.0545485 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 312 313 2.59115 0.0146552 -0.0545087 0.00410721 0.0378454 0.0866658 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 263 313 0.041537 -3.11484 -0.211902 0.0519565 0.0146515 -0.0366972 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 313 314 2.7719 0.0842506 0.00799343 0.00496255 0.05914 0.0863856 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 264 314 0.0122075 -2.67492 -0.159409 0.0574287 -0.0123743 0.0430818 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 314 315 2.59943 0.08656 0.0773209 0.0114575 0.061365 0.129965 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 265 315 0.0623737 -3.07501 -0.135195 0.0678648 0.00309969 0.0473259 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 315 316 2.56185 -0.038594 -0.130812 0.0146796 0.0591207 0.111583 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 266 316 0.0202681 -3.02132 -0.108423 0.0636476 -0.00817666 0.00235996 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 316 317 2.58343 0.0497491 0.0273671 -0.0138387 0.0544616 0.0936768 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 267 317 -0.157225 -3.18032 -0.0391657 0.0513371 -0.00506462 0.0475 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 317 318 2.45417 -0.0622298 0.0542601 0.00629408 0.0499152 0.150717 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 268 318 0.227863 -2.92362 -0.0551483 0.0629681 -0.0186735 -0.0347945 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 318 319 2.5998 -0.0572395 -0.184706 0.014423 0.03419 0.13126 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 269 319 0.150875 -3.14073 0.056212 0.0565669 -0.0224126 -0.0450683 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 319 320 2.69845 0.0876705 -0.0726314 0.0124856 0.0467442 0.0674456 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 270 320 0.0302405 -2.94097 0.0195797 0.0521747 0.00694305 -0.001221 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 320 321 2.64474 -0.141128 -0.0760252 0.00991935 0.0306692 0.168295 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 271 321 0.111483 -2.98989 -0.0668654 0.0551202 -0.000331409 -0.0557024 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 321 322 2.53724 0.0399798 -0.0673388 0.00503454 0.054849 0.119775 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 272 322 -0.0252455 -3.08534 -0.0673068 0.0588059 -0.00231154 -0.0192559 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 322 323 2.64459 0.197896 0.086238 -0.0188356 0.0652948 0.103952 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 273 323 0.0460613 -3.01295 -0.117746 0.0455812 0.00663504 0.0431067 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 323 324 2.74405 0.118855 -0.128794 0.00338399 0.0597662 0.0975454 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 274 324 0.00630421 -3.02644 -0.0487656 0.0589253 -0.00266446 0.0222746 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 324 325 2.79623 0.150104 -0.103291 0.00423849 0.0476681 0.119731 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 275 325 0.158625 -3.15376 -0.134453 0.0507231 0.0156692 0.0396078 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 325 326 2.58383 0.101972 0.0547001 -0.00101533 0.069927 0.0714858 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 276 326 0.048248 -2.98662 -0.0409321 0.0432863 0.00107726 0.0014342 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 326 327 2.73928 0.236487 -0.0642725 0.00747905 0.0165434 0.185547 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 277 327 0.13536 -3.03136 -0.0904836 0.0734037 -0.0135481 0.00495507 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 327 328 2.5945 0.328433 -0.0731877 0.0037788 0.0487799 0.15722 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 278 328 0.0149143 -3.15991 -0.126968 0.0527968 -0.000477374 8.30888e-06 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 328 329 2.71027 0.159758 -0.00752501 -0.0096679 0.0410819 0.0840555 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 279 329 0.0451922 -3.16909 -0.140876 0.0608477 -0.00631788 0.023486 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 329 330 2.74073 0.181573 -0.0288775 0.014218 0.0470764 0.0647657 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 280 330 0.0695638 -3.07913 -0.0356025 0.0481555 0.00100569 -0.0310602 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 330 331 2.80562 -0.00400767 -0.165928 0.0180792 0.040529 0.158776 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 281 331 0.0315745 -3.1598 -0.233664 0.0617464 0.00124763 0.0260476 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 331 332 2.65997 -0.0256876 -0.0245655 0.00993111 0.048713 0.107842 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 282 332 -0.0577875 -2.93112 -0.122457 0.0588323 -0.00405377 0.0489408 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 332 333 2.61047 0.0522071 -0.053205 0.00120208 0.0543207 0.147944 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 283 333 -0.0268156 -2.75783 -0.115114 0.0546577 0.0162552 0.0115813 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 333 334 2.66212 0.106019 -0.0891965 -0.00732021 0.0635404 0.0916861 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 284 334 -0.0721355 -3.09307 -0.013885 0.0685537 0.00030565 -0.0448545 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 334 335 2.86176 0.0803541 0.0339033 0.0109522 0.0376732 0.0752878 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 285 335 0.150753 -2.80772 -0.149334 0.0611653 -0.0332896 -0.0561361 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 335 336 2.63173 0.0857922 -0.0765264 1.53475e-05 0.052641 0.122235 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 286 336 0.0608423 -3.02065 -0.0145856 0.0561999 0.0129869 0.0281077 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 336 337 2.63794 0.162968 -0.0143013 0.00197288 0.065805 0.0636246 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 287 337 -0.0255246 -3.05047 -0.185222 0.070739 -0.00597479 0.00128604 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 337 338 2.86214 0.133707 0.0364661 0.00436976 0.0625681 0.142672 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 288 338 0.0331453 -3.00436 -0.0687598 0.0588309 -0.00273267 -0.0396027 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 338 339 2.85028 0.00576298 -0.04141 0.0130163 0.0583887 0.142645 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 289 339 0.0314378 -2.99084 -0.0456048 0.0604781 0.00116494 -0.0513464 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 339 340 2.71056 0.189705 -0.199337 0.000398493 0.066848 0.118615 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 290 340 0.0876317 -3.21416 -0.0478817 0.0728223 -0.018189 0.0330845 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 340 341 2.73563 0.14105 -0.210063 0.0139426 0.0607439 0.0944863 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 291 341 -0.0927587 -3.09953 0.0212842 0.0511708 -0.00457383 0.00536161 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 341 342 2.8134 0.160499 -0.0633969 0.000677356 0.0660403 0.111132 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 292 342 -0.152173 -3.15096 0.123591 0.0775026 -0.00439625 0.0413479 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 342 343 2.9477 0.0578942 -0.185103 0.0185431 0.0479529 0.0581119 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 293 343 -0.0792689 -2.99066 -0.176326 0.051252 -0.00702787 0.0431172 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 343 344 2.87939 0.28442 0.111384 0.00133339 0.0366732 0.110842 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 294 344 -0.0749327 -3.07287 -0.169298 0.0534514 0.000271136 0.000986308 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 344 345 2.79356 0.136136 -0.163805 -0.00194104 0.0379549 0.0219771 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 295 345 -0.0298243 -3.06462 -0.058291 0.0709493 -0.00815554 0.0317147 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 345 346 2.84246 0.109173 -0.141872 -0.00920729 0.0553079 0.154226 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 296 346 -0.208389 -3.11332 -0.158929 0.0642027 -0.00334567 0.042405 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 346 347 2.84809 0.131258 -0.0112449 -0.0014044 0.0652313 0.189728 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 297 347 0.00397964 -3.16043 -0.229948 0.0614931 -0.0160772 0.0761069 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 347 348 3.03374 0.123149 0.0392922 0.02612 0.0543123 0.0898261 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 298 348 0.0542878 -2.83593 0.0760777 0.0643477 -0.00150513 0.00642693 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 348 349 2.71507 0.0797169 -0.0195319 0.0020167 0.0532774 0.105998 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 299 349 0.0954617 -2.9754 -0.130473 0.0654208 0.00382247 0.0785619 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 349 350 2.82924 -0.026305 -0.0527465 -0.0111115 0.0483014 0.10985 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 300 350 -0.0343199 -3.01386 -0.138736 0.0540196 0.0109195 0.0138185 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 350 351 2.87978 0.000666609 0.00867498 0.00593418 0.0544811 0.0584537 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 301 351 0.265006 -3.15289 -0.019854 0.0473533 0.00963643 -0.0199246 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 351 352 2.8458 0.130492 0.00630286 0.00456671 0.0575172 0.14053 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 302 352 -0.117375 -3.10649 -0.151037 0.0430529 -0.0114369 0.0337997 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 352 353 2.89921 0.207804 0.139018 0.00202502 0.0480767 0.137702 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 303 353 -0.1724 -3.12157 0.204506 0.0501468 -0.0168333 -0.0626732 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 353 354 3.03432 0.108421 -0.201936 0.000991819 0.0624457 0.054975 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 304 354 0.0457296 -3.00187 -0.21433 0.0588106 0.0153098 0.0108644 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 354 355 2.83666 0.0997601 0.117516 0.00752237 0.0664889 0.0882141 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 305 355 0.0365762 -3.20068 -0.120433 0.0711442 -0.00588895 0.0200344 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 355 356 2.83688 -0.108716 -0.142772 -0.0086111 0.0542311 0.141148 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 306 356 -0.0840794 -2.99812 -0.0461709 0.0632397 0.0118873 0.0279077 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 356 357 2.93553 0.148458 -0.31026 0.00595053 0.0478201 0.248812 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 307 357 0.123624 -3.1738 -0.232172 0.0714473 0.00122137 0.000212123 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 357 358 2.86284 0.062805 -0.0995848 0.00610352 0.0736154 0.1608 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 308 358 0.184947 -2.95908 0.074224 0.0727213 0.00146253 0.0233154 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 358 359 2.82224 0.228264 -0.179339 0.00612176 0.0558687 0.100173 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 309 359 -0.0679075 -2.92765 0.0616984 0.0608368 -0.00528454 0.101143 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 359 360 2.87326 -0.0120272 0.0680689 -0.00286332 0.0477168 0.124242 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 310 360 -0.0660665 -3.25747 -0.0252614 0.0494632 -0.00833563 -0.0461579 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 360 361 2.94578 0.103857 -0.00621059 0.0131982 0.0482684 0.105892 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 311 361 -0.0881092 -2.99737 -0.115497 0.0512331 0.00978022 0.00682433 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 361 362 2.87397 0.145398 -0.125625 -0.0199799 0.0539534 0.134913 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 312 362 -0.0289822 -3.03785 -0.0624406 0.0707626 0.00670005 -0.0375735 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 362 363 2.66867 0.067003 -0.117472 -0.00118966 0.0740494 0.104503 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 313 363 -0.151813 -3.28227 -0.277165 0.0543925 -0.00365733 0.0230941 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 363 364 2.91263 -0.0694548 -0.160375 0.00735127 0.082979 0.112313 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 314 364 -0.00254953 -3.19376 -0.00343866 0.033928 0.00799826 -0.035226 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 364 365 2.91952 0.129288 -0.168713 0.00877359 0.0726576 0.143324 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 315 365 0.0155068 -2.96301 -0.179671 0.0512492 0.00806169 -0.0143289 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 365 366 2.94564 0.101368 -0.0217288 0.0142392 0.0715118 0.150179 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 316 366 0.0664133 -3.11125 -0.0599331 0.0628588 -0.00326163 0.0553416 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 366 367 3.05253 0.227679 0.0875629 0.000632479 0.0526161 0.0772915 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 317 367 -0.1074 -3.00215 0.0437778 0.0586543 0.00157632 -0.0105174 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 367 368 2.90293 -0.113606 -0.0359419 0.00282247 0.0482182 0.0628278 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 318 368 0.0884503 -3.14416 -0.241082 0.0785013 -0.000574608 -0.00577866 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 368 369 2.73985 0.213837 0.0781447 0.0299315 0.0574055 0.153566 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 319 369 -0.129026 -3.04014 0.0962665 0.076494 0.00602457 -0.00764817 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 369 370 2.96903 0.0841959 -0.012548 0.0076488 0.0522346 0.113021 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 320 370 0.0266504 -3.09222 -0.0154214 0.0835037 -7.04221e-05 -0.0160302 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 370 371 3.04959 0.17682 0.0770593 0.00945497 0.05475 0.106421 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 321 371 0.0231897 -3.04714 -0.174079 0.0492951 -0.00102889 0.00799371 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 371 372 2.87679 0.0868652 -0.348639 0.0100684 0.0743655 0.119378 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 322 372 0.0857668 -3.07846 -0.175278 0.051206 0.00428826 0.0216727 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 372 373 3.15181 0.0931108 -0.130737 0.00331165 0.0582827 0.119341 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 323 373 0.0151937 -3.11577 -0.0335541 0.0614269 -0.00985371 0.0710828 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 373 374 2.9804 0.0300695 -0.133022 0.0179785 0.0725955 0.122143 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 324 374 -0.0533005 -2.9534 -0.0210836 0.0564708 -0.00443932 -0.0140842 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 374 375 2.796 0.119305 -0.132021 0.0156483 0.0530531 0.0863005 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 325 375 -0.0850833 -3.09657 0.0424286 0.0625068 -0.00282612 -0.0451653 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 375 376 2.97303 0.0353721 -0.0658551 -0.00465192 0.0806502 0.0483663 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 326 376 0.0681386 -3.14417 -0.0568083 0.0543433 0.0102875 0.0369799 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 376 377 2.90809 0.096925 -0.0287028 0.00475966 0.0667139 0.0328017 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 327 377 -0.0986384 -3.04283 -0.00246123 0.0684494 0.012665 0.0220771 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 377 378 2.86714 -0.140645 0.0190846 -0.000852787 0.0561766 0.168859 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 328 378 0.0270612 -3.18904 0.0068394 0.0582885 0.00551692 -0.0587517 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 378 379 2.98309 0.0224041 -0.0317134 0.0187183 0.0575962 0.155708 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 329 379 0.0423988 -3.14623 0.00629121 0.0728886 -0.0101116 0.0430335 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 379 380 3.07073 0.0327595 -0.0758744 0.000379658 0.0556845 0.186298 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 330 380 0.0400586 -3.17669 -0.00120155 0.0743761 -0.00873533 -0.00679735 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 380 381 3.10564 0.0907773 0.0914588 0.00644539 0.0677491 0.0982332 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 331 381 0.0515707 -2.98244 -0.119449 0.0673407 -0.00682151 0.0132342 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 381 382 3.16325 0.0180853 -0.0669987 0.00318931 0.0639728 0.0649999 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 332 382 -0.121467 -3.06315 -0.137284 0.0851848 0.00636444 -0.0091023 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 382 383 3.03272 -0.00647344 -0.0858751 0.000451769 0.0519935 0.0546537 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 333 383 0.0810237 -2.98352 -0.079982 0.0614974 0.000664671 -0.0186466 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 383 384 3.10634 0.144404 -0.304956 0.00345544 0.07107 0.134859 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 334 384 -0.0612038 -3.14884 0.0278424 0.0738103 0.00823268 -0.0308931 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 384 385 3.18203 0.08945 -0.147059 0.0115985 0.0658424 0.0916337 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 335 385 -0.0917869 -2.89855 -0.0774573 0.0757601 -0.00317688 -0.0486844 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 385 386 3.11767 0.0502868 -0.0732789 -0.00248194 0.0682921 0.150294 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 336 386 0.023934 -3.0237 -0.194363 0.061112 -0.00524443 0.0195153 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 386 387 3.01447 0.081949 -0.00580409 0.00122972 0.0599023 0.147966 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 337 387 0.112594 -3.22375 -0.258141 0.0617473 0.00743139 -0.0409924 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 387 388 3.20588 0.200952 -0.109076 0.0365328 0.0559534 0.106005 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 338 388 -0.122149 -3.1064 -0.180947 0.0534253 -0.00151982 0.0530027 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 388 389 3.08185 -0.0043165 -0.198868 0.00502045 0.0700785 0.0533675 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 339 389 -0.122625 -3.14797 -0.063126 0.0711918 0.00297775 -0.0206773 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 389 390 3.19034 -0.0125952 -0.105443 -0.012163 0.0735104 0.0541364 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 340 390 0.0557067 -3.0186 -0.180773 0.0594348 0.0214338 -0.0393865 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 390 391 3.11216 0.162806 -0.267381 0.0124649 0.0664924 0.0946969 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 341 391 -0.0238847 -3.08454 -0.120323 0.0642753 -0.00845573 -0.0514858 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 391 392 2.97079 0.13584 -0.1802 -0.0142952 0.067535 0.0966197 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 342 392 0.0492906 -3.05011 -0.0925048 0.064389 0.0247469 -0.041795 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 392 393 3.20136 0.202724 -0.0513181 0.0136725 0.0615387 0.0576334 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 343 393 0.18446 -2.95983 -0.0489129 0.0635761 0.0140854 -0.0382634 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 393 394 3.30615 0.147441 -0.0178528 0.00853044 0.0692574 0.0965268 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 344 394 0.0987677 -3.08234 -0.146997 0.0623897 -0.0125023 0.01614 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 394 395 3.10456 0.186036 -0.10306 0.0118121 0.0592698 0.0647979 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 345 395 -0.0766605 -3.20372 -0.188753 0.0545575 -0.00429321 -0.00106916 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 395 396 3.02261 0.0745221 -0.211983 0.0163996 0.0649906 0.146119 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 346 396 -0.0504546 -3.05566 -0.0827472 0.0635477 0.0132165 0.00471594 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 396 397 3.18018 0.0461198 0.0624689 0.0192863 0.0663766 0.0862823 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 347 397 0.109153 -3.0851 -0.209512 0.0537192 0.000488301 0.0163928 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 397 398 3.07187 0.124298 0.0504869 0.00819872 0.0763682 0.144783 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 348 398 0.0309543 -3.08974 -0.13822 0.0522938 0.00771685 0.0370596 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 398 399 3.19152 0.0914991 -0.142671 -0.00253466 0.0703534 0.107224 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 349 399 0.0265289 -2.91285 0.0861061 0.0665995 -0.00752491 -0.0341986 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 399 400 3.21972 0.149408 -0.172255 -0.0062377 0.0598966 0.1133 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 350 400 -0.0421807 -3.24188 0.065461 0.064132 -0.00978236 -0.00385851 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 400 401 3.27413 -0.024151 -0.182691 0.0023934 0.0673349 0.128761 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 351 401 0.0413224 -3.1157 -0.233956 0.0660047 0.00178252 -0.0124006 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 401 402 3.16193 0.214827 -0.189693 0.00562081 0.0492187 0.125822 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 352 402 -0.083502 -3.1765 -0.257381 0.0704937 0.00282212 -0.0634518 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 402 403 3.23378 -0.0293437 -0.0900133 0.0226492 0.0413576 0.150006 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 353 403 -0.0650663 -3.24076 -0.139133 0.0625174 0.00108883 -0.0155092 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 403 404 3.22247 -0.0128357 -0.141105 -0.0134586 0.0705725 0.121427 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 354 404 -0.192399 -3.05254 -0.0205584 0.060591 0.0002854 -0.013883 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 404 405 3.12734 0.0737837 -0.330096 -0.000906265 0.0869039 0.12337 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 355 405 -0.0605368 -2.91813 0.151889 0.0654096 0.0185753 -0.0576067 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 405 406 3.32 -0.0202808 -0.182474 -0.00161277 0.061404 0.143872 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 356 406 0.0697443 -3.11318 -0.0605606 0.0608481 -0.00977865 0.0313103 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 406 407 3.39081 0.0510789 0.0479507 0.00910013 0.0652233 0.0363149 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 357 407 -0.052607 -3.14251 -0.256375 0.0736337 0.00172698 -0.0436513 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 407 408 3.26193 0.161083 -0.0500117 0.0015418 0.0720797 0.0593477 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 358 408 0.112514 -2.98367 0.0173553 0.0602897 -0.0090976 0.0378503 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 408 409 3.31422 0.155672 0.0320465 0.00767183 0.0415094 0.0580505 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 359 409 -0.0525742 -3.20008 -0.0944529 0.0493181 -0.00233522 -0.0687765 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 409 410 3.12657 0.253023 -0.0846193 0.0123177 0.0763351 0.0350927 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 360 410 -0.18415 -2.94843 -0.074468 0.0568125 -0.00028706 -0.0179449 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 410 411 3.37265 0.028787 -0.074283 0.0056486 0.0545174 0.0537736 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 361 411 -0.0716385 -3.01298 -0.0871289 0.0651812 -0.00308784 -0.0166344 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 411 412 3.4127 0.00462193 -0.204093 -0.00795592 0.0584474 0.0656573 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 362 412 0.0542683 -3.23037 -0.117154 0.0679359 0.000893003 0.0105506 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 412 413 3.22292 0.103352 -0.0944368 -0.00684744 0.09333 -0.00604946 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 363 413 0.013873 -3.02507 -0.102966 0.082015 -0.00501019 0.00471072 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 413 414 3.26788 0.0146335 0.0374291 0.00842318 0.0859766 0.180298 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 364 414 -0.0182592 -2.94417 -0.00237069 0.0639197 -0.000574346 0.0147323 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 414 415 3.17238 0.0633887 -0.0437359 0.0187326 0.0652702 0.125705 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 365 415 -0.11561 -3.28737 -0.263701 0.0582578 -0.00499865 0.0455227 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 415 416 3.30838 0.0944925 -0.0954845 0.00729597 0.0607829 0.126268 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 366 416 0.0202636 -2.92963 -0.109526 0.068734 -0.00326315 0.055255 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 416 417 3.23944 0.0461074 -0.0681797 0.00509117 0.0769717 0.132596 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 367 417 -0.0540784 -3.02968 0.04813 0.0539106 0.00124784 0.0076004 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 417 418 3.26348 0.127138 -0.1021 0.00996694 0.0555856 0.127564 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 368 418 -0.175451 -3.09671 -0.0820867 0.0601473 0.000380817 -0.061502 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 418 419 3.2143 0.22254 -0.0195218 0.00763005 0.0674576 0.064736 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 369 419 0.0532406 -3.03388 -0.175604 0.0451139 -0.000250139 0.0104006 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 419 420 3.35026 -0.0314446 -0.122256 -0.000908794 0.0857293 0.149367 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 370 420 -0.0564968 -3.09617 -0.0723869 0.040321 -0.00654928 0.0210118 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 420 421 3.35593 0.166072 0.00112407 0.00736939 0.0619274 0.0813255 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 371 421 -0.0627655 -3.09987 -0.098957 0.0603596 -0.00491288 0.0348535 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 421 422 3.41509 0.201902 -0.191458 0.0156394 0.060328 0.0575159 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 372 422 -0.171848 -3.312 -0.154478 0.0706557 -0.00784438 -0.0270189 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 422 423 3.5661 -0.0468487 -0.141353 0.0126043 0.0628571 0.103265 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 373 423 -0.0468701 -3.1413 -0.0624481 0.0659145 -0.00731169 -0.00254067 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 423 424 3.3959 0.122381 -0.136459 -0.0016161 0.0566852 0.0991456 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 374 424 0.088291 -3.02906 -0.155652 0.0665207 0.0031223 0.0225128 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 424 425 3.21485 -0.0281558 0.0346627 1.70487e-05 0.0655007 0.0809431 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 375 425 0.207394 -2.91419 -0.114998 0.0443429 0.00476568 -0.00916546 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 425 426 3.30277 -0.0664087 -0.201607 -0.000455865 0.0718705 0.0716525 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 376 426 0.0181117 -3.01259 0.000238796 0.0600674 0.00945289 -0.0117362 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 426 427 3.2611 0.114489 -0.231325 -0.00404 0.0563417 0.164283 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 377 427 -0.041838 -3.06789 -0.0795635 0.0490841 0.025016 -0.00609523 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 427 428 3.37976 0.141219 -0.306502 0.0166451 0.0717761 0.187493 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 378 428 0.0931215 -2.97914 -0.308081 0.0706244 0.0190079 -0.0114075 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 428 429 3.31658 -0.058278 -0.173215 -0.0041398 0.0666654 0.162559 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 379 429 0.0257219 -3.1835 -0.15155 0.0603111 -0.0197848 0.0457061 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 429 430 3.3345 0.102947 -0.105852 0.0042141 0.0684127 0.113874 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 380 430 -0.0319896 -3.33208 -0.0583484 0.0570383 0.00351714 -0.0468665 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 430 431 3.35613 0.0908043 -0.205256 0.00772584 0.0845123 0.102353 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 381 431 0.126897 -3.13356 -0.14294 0.0759472 0.0126129 -0.0126956 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 431 432 3.29621 0.199104 -0.10716 0.00594896 0.0771551 0.118976 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 382 432 0.0565417 -3.26596 -0.108116 0.0541018 -0.00129124 0.0238849 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 432 433 3.45039 0.344012 -0.170228 0.0105124 0.0711753 0.0548195 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 383 433 0.07558 -3.15481 -0.213848 0.0563858 -0.00896761 -0.0022658 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 433 434 3.32673 0.157965 -0.025901 0.0148389 0.077518 0.127199 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 384 434 0.0770277 -3.0559 0.0140446 0.0620608 -0.00685316 0.0523082 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 434 435 3.27829 0.135749 -0.18293 0.0177394 0.0777283 0.053291 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 385 435 -0.0283599 -3.1751 -0.271241 0.0682922 0.0110072 0.0185807 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 435 436 3.56308 0.192495 0.0145542 0.00651771 0.0713745 0.167788 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 386 436 0.1967 -3.05667 -0.0109382 0.0712059 -0.000642856 -0.0140095 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 436 437 3.20551 0.0425734 -0.168717 0.00981742 0.0820111 0.0857287 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 387 437 0.109931 -2.92796 0.0553454 0.0355482 -0.015978 0.0121646 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 437 438 3.39451 0.209493 -0.20637 -0.00910851 0.0772339 0.0799571 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 388 438 0.00671874 -3.11942 -0.0945887 0.0512102 -0.00634607 0.000368925 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 438 439 3.18075 -0.080392 -0.132056 -0.0025742 0.042594 0.109325 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 389 439 0.032196 -3.17175 -0.172647 0.0502252 -0.00628953 -0.0250875 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 439 440 3.54228 0.143921 -0.241116 0.00100928 0.0578819 0.158373 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 390 440 -0.033753 -3.14126 -0.147433 0.0719109 0.00547693 0.0763904 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 440 441 3.38823 -0.051158 -0.0980165 0.0144754 0.0684642 0.125917 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 391 441 -0.0315664 -3.1566 -0.00745872 0.0656866 -0.0134408 -0.0209012 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 441 442 3.27827 0.124023 -0.102063 -0.00416668 0.0736536 0.0532165 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 392 442 -0.0306541 -3.08218 0.0422496 0.0601903 -0.000588123 -0.0067049 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 442 443 3.56728 -0.0719442 -0.377339 0.00757625 0.07661 0.118502 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 393 443 0.102152 -3.07496 -0.0456719 0.056529 -0.00136995 -0.0137568 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 443 444 3.62625 0.0721493 -0.156417 0.0222885 0.0759356 0.107998 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 394 444 -0.0507474 -3.10341 0.0431926 0.0732952 -0.00367414 -0.00546226 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 444 445 3.32187 0.127136 -0.110797 0.0263874 0.0819347 0.117101 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 395 445 -0.0172256 -3.22721 -0.117645 0.061752 -0.00315061 -0.0430562 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 445 446 3.53989 0.127564 -0.0473487 0.0056888 0.0652421 0.121905 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 396 446 0.106587 -3.11316 0.0185749 0.0484163 -0.0063512 -0.0209178 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 446 447 3.58459 -0.00379123 -0.0336647 0.0219403 0.0659642 0.116624 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 397 447 -0.0201798 -3.03708 -0.0914904 0.0655264 -0.00178806 -0.0116168 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 447 448 3.46325 0.173719 -0.0595293 0.00733091 0.0624233 0.157544 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 398 448 -0.147206 -3.16075 -0.0171375 0.065731 -0.00422425 -0.0618062 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 448 449 3.55411 0.204853 -0.184507 -0.00155623 0.0502297 0.0839438 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 399 449 -0.104981 -3.10923 -0.0205621 0.0603971 0.00120703 -0.0118557 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 449 450 3.57962 0.0782268 -0.119861 0.0147521 0.0724566 0.0747318 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 400 450 -0.203892 -3.06867 0.0130038 0.0517254 -0.0102964 -0.0364815 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 450 451 3.35634 0.127703 0.102256 0.00931259 0.0601557 0.133427 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 401 451 -0.0173478 -2.99093 -0.184401 0.0628268 -0.0151161 -0.00193195 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 451 452 3.61229 0.184675 -0.168935 0.00261009 0.067708 0.103225 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 402 452 0.0359814 -3.03873 -0.0784567 0.0661043 0.020562 0.0101725 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 452 453 3.57427 0.0722839 -0.0655716 0.00413538 0.0886351 0.0986128 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 403 453 -0.022771 -3.00832 0.0193771 0.0630506 0.00120391 0.0182758 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 453 454 3.47514 0.116031 -0.215117 0.0112577 0.0862787 0.118197 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 404 454 -0.0361572 -3.00766 0.0409691 0.0728597 0.0131933 0.0233485 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 454 455 3.61715 0.0685614 -0.0014102 0.0126773 0.072259 0.113569 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 405 455 -0.031604 -2.83553 -0.119168 0.0580639 -0.00373161 0.0470486 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 455 456 3.45329 0.18322 -0.121366 0.0148615 0.0841383 0.070395 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 406 456 0.0127513 -3.19293 -0.0453915 0.0653588 -0.00340459 -0.0137889 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 456 457 3.76647 0.211655 -0.347048 0.00476863 0.0812274 0.176235 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 407 457 -0.0906149 -2.99691 -0.172306 0.066498 -0.0062711 0.00669413 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 457 458 3.4447 0.189049 -0.00781451 0.00164876 0.0805827 0.190063 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 408 458 0.121398 -3.02982 -0.363333 0.0581788 -0.00173128 -0.0916576 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 458 459 3.53498 0.0785846 0.0688918 -0.00562856 0.0728812 0.0453671 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 409 459 0.00134455 -3.14766 -0.0476588 0.058278 -0.00106286 0.0183033 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 459 460 3.60933 0.123437 -0.309198 -0.00327918 0.0661405 0.122024 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 410 460 0.0447064 -3.27094 -0.141518 0.0585911 -0.00702426 -0.0335374 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 460 461 3.38766 0.201033 -0.133137 0.00358922 0.0955989 0.121226 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 411 461 -0.0889622 -2.85268 -0.0480516 0.0647974 0.00941662 -0.0388561 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 461 462 3.51512 0.221229 -0.173054 0.00618404 0.0712243 0.162774 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 412 462 0.0372867 -3.18528 -0.271924 0.0573535 -0.00743599 0.102081 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 462 463 3.54555 0.142099 -0.169522 0.000488576 0.074359 0.107033 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 413 463 0.096881 -3.08444 -0.144603 0.0663503 -0.00937494 0.0398517 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 463 464 3.54701 0.145732 -0.306492 -0.0011144 0.0835083 0.0511724 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 414 464 -0.0822471 -3.01655 -0.0870149 0.0693481 0.012466 -0.0123817 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 464 465 3.62741 0.0754943 -0.233159 0.00765328 0.065801 0.13613 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 415 465 0.119231 -2.87575 0.0312047 0.0476469 -0.00013909 -0.00460523 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 465 466 3.60857 -0.0900581 -0.286237 0.0189407 0.0598527 0.144245 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 416 466 -0.0238928 -2.89703 -0.104066 0.0461448 -0.00695667 0.0236071 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 466 467 3.59722 0.203756 -0.0427307 0.00596031 0.0457527 0.151585 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 417 467 0.00737793 -3.0064 -0.10457 0.0651257 -0.00994244 0.00527011 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 467 468 3.56376 0.162283 -0.100662 0.0098684 0.0832587 0.121443 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 418 468 -0.117599 -3.19109 -0.0209419 0.058818 0.000310715 -0.0133034 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 468 469 3.54669 -0.0492029 0.00153818 -0.00898604 0.063461 0.153763 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 419 469 -0.137726 -3.07157 -0.293235 0.0562408 3.93579e-05 0.0395334 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 469 470 3.64499 0.0668751 0.0793052 0.00728216 0.0634792 0.0813333 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 420 470 -0.0588484 -2.98912 0.0163386 0.0462394 -0.00551386 -0.0118488 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 470 471 3.69806 0.169708 -0.211487 0.0106137 0.0811955 0.0964504 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 421 471 0.0588939 -3.08021 -0.274182 0.069182 0.00438603 0.0226383 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 471 472 3.49565 0.182365 -0.168005 0.0145362 0.0860038 0.147629 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 422 472 0.0998706 -3.09977 -0.117523 0.0753753 -0.000740373 0.0663712 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 472 473 3.62298 0.0511005 -0.266726 0.0112909 0.0735707 0.0828631 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 423 473 -0.245608 -3.16258 0.0298535 0.0619629 0.0127773 -0.0207177 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 473 474 3.71147 0.192303 -0.091043 0.00835421 0.084388 0.161083 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 424 474 -0.0366605 -3.16246 -0.275683 0.0728952 -0.00321742 0.0235333 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 474 475 3.74325 0.0567789 -0.0913575 0.0199787 0.0675884 0.142338 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 425 475 -0.00977704 -3.09312 -0.100344 0.0779361 -0.00936006 0.00371811 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 475 476 3.59765 -0.10032 -0.0151919 0.0116111 0.0798173 0.0648273 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 426 476 -0.111029 -3.08446 -0.211274 0.0679393 0.00530336 0.0359134 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 476 477 3.67405 0.121143 -0.100621 -0.00723202 0.0727352 0.0518767 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 427 477 -0.0108214 -3.09198 -0.0355495 0.0575443 0.00591971 0.0289628 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 477 478 3.62676 0.177563 -0.174458 0.00410312 0.0693503 0.0994985 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 428 478 -0.0573733 -3.1696 -0.106993 0.0848252 -0.00389152 0.0292275 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 478 479 3.67612 0.158047 -0.357277 0.0111516 0.0806011 0.112475 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 429 479 0.163057 -2.92047 -0.175626 0.0578112 -0.00673874 0.00383637 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 479 480 3.60555 0.204163 -0.266459 0.00292518 0.062502 0.127485 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 430 480 0.0446952 -3.1157 0.0497409 0.0591882 0.00596649 0.0160401 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 480 481 3.65388 0.054029 -0.316871 0.00326098 0.0733995 0.117662 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 431 481 0.0376101 -3.07516 0.0221836 0.0616573 -0.00502553 0.00636831 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 481 482 3.86591 0.0935133 -0.0553218 0.00236865 0.0758955 0.122872 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 432 482 0.0519618 -3.10432 -0.0415326 0.046882 -0.0021714 0.0118425 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 482 483 3.65019 0.18456 -0.190368 -0.0110337 0.0642148 0.0859518 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 433 483 0.0776679 -2.84919 -0.135489 0.0635802 0.0168134 -0.032814 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 483 484 3.69693 0.0751205 -0.291048 -0.00694089 0.0649147 0.0681274 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 434 484 -0.117491 -2.89128 -0.0367233 0.0665251 -0.0060374 0.0642309 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 484 485 3.62024 0.27103 -0.0687773 0.00762217 0.0713111 0.0696647 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 435 485 -0.1062 -2.99011 -0.142849 0.0652837 -0.00187974 0.0201052 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 485 486 3.77084 0.313037 -0.115862 -0.00445653 0.0944266 0.115348 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 436 486 -0.000317152 -2.9345 -0.204794 0.051365 0.0059283 0.00284339 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 486 487 3.70517 0.187198 -0.129466 -0.00885559 0.0931207 0.115496 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 437 487 -0.0508378 -3.03232 -0.0248464 0.079242 -0.0147366 -0.00104854 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 487 488 3.8475 0.256771 -0.130784 0.00299356 0.0930348 0.0788507 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 438 488 -0.0578187 -2.9426 -0.145818 0.0651443 -0.007795 -0.0723541 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 488 489 3.78842 0.0223509 -0.0382019 -0.00377433 0.0779189 0.146746 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 439 489 -0.087692 -2.96877 0.0486791 0.0458999 0.00524889 0.00396505 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 489 490 3.88276 0.158716 -0.180889 0.00116958 0.0754741 0.178986 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 440 490 -0.101993 -3.2531 -0.163744 0.0646804 -0.0151943 -0.0614372 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 490 491 3.75782 0.083999 -0.1481 0.00357087 0.0620913 0.00107785 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 441 491 -0.0548397 -2.97261 -0.161954 0.0606027 0.00948554 0.0115832 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 491 492 3.77221 -0.111307 -0.254365 0.00197053 0.0667299 0.080233 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 442 492 0.0476361 -3.03631 -0.0250002 0.0598625 0.00977126 -0.00378224 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 492 493 3.58833 0.0925936 -0.145602 0.0288871 0.0722581 0.11045 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 443 493 0.214312 -2.99151 -0.150953 0.0649247 -0.00125136 0.0266043 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 493 494 3.82132 0.0112118 -0.245382 0.00614675 0.051671 0.0942329 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 444 494 -0.0656956 -3.17403 -0.0652417 0.0607093 -0.009534 0.0424553 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 494 495 3.82029 0.2063 -0.203608 0.0130572 0.0748444 0.141814 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 445 495 -0.0713465 -2.86925 0.0338818 0.0709912 -0.000325425 -0.00895378 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 495 496 3.76289 0.134068 -0.0645702 -0.0100058 0.0697079 0.154513 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 446 496 0.0593604 -3.02213 -0.113658 0.0699398 0.00136843 -0.0636795 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 496 497 3.73 0.173224 -0.328378 0.00436913 0.0666895 0.130199 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 447 497 -0.0463884 -3.06277 0.0458042 0.0477075 0.0163994 -0.0263504 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 497 498 3.84273 0.145939 -0.220872 -0.0154486 0.0743354 0.12186 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 448 498 0.0517956 -2.92205 -0.0539414 0.0542212 -0.00577298 0.101138 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 498 499 3.79888 0.0821883 -0.08635 0.0020933 0.0656837 0.0278159 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 449 499 0.110917 -3.00957 -0.0831002 0.0638767 -0.00309468 -0.0415856 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 499 500 3.83306 0.0759601 -0.253652 0.0139164 0.0817269 0.0839091 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 450 500 0.0434672 -2.90754 -0.0126111 0.0676594 0.0183853 0.0524981 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 500 501 3.85151 0.138466 0.128253 -0.00870097 0.0904362 0.194709 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 451 501 -0.0013868 -3.14524 -0.00917391 0.0632742 0.0126577 -0.0189674 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 501 502 3.91966 0.0524988 -0.0996591 -0.00861704 0.0857304 0.165154 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 452 502 -0.275645 -3.12191 -0.0770046 0.0442581 0.00897228 0.0148245 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 502 503 3.98606 0.194653 -0.345098 0.0246064 0.0880796 0.134648 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 453 503 0.0725374 -3.00983 0.0475128 0.067025 -0.000981525 -0.0277845 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 503 504 3.73441 0.108589 -0.160056 0.00124094 0.0802607 0.0750512 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 454 504 0.123422 -3.18604 -0.0824937 0.062116 -0.0122956 -0.0437691 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 504 505 3.78242 0.0320403 -0.322713 0.0137592 0.0790056 0.0854509 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 455 505 0.11624 -3.08774 -0.0372738 0.0729123 0.00194156 -0.0251189 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 505 506 3.70364 0.0432564 -0.226615 -0.00139495 0.0766945 0.128247 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 456 506 0.0899581 -3.09202 -0.191797 0.0614763 0.00428884 -0.0322435 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 506 507 3.91129 0.000431945 -0.0944495 0.0340613 0.0992868 0.0908592 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 457 507 -0.0583982 -2.92281 -0.123895 0.0648013 -0.00474148 -0.0584832 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 507 508 3.97862 0.213963 0.00115162 0.0211217 0.0786748 0.0448445 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 458 508 -0.0224024 -3.01623 -0.00626124 0.0559473 -0.0151359 -0.0247848 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 508 509 3.96986 0.0386509 -0.109516 0.00646992 0.0679851 0.106532 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 459 509 0.00568359 -3.23055 -0.0902167 0.0637837 0.00321402 0.0295698 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 509 510 3.81819 -0.0859875 -0.110866 -0.00463445 0.0766746 0.119883 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 460 510 0.0356975 -3.09423 -0.138503 0.0594513 0.00653494 0.016994 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 510 511 3.91914 0.03392 -0.133456 0.0113921 0.0735092 0.0521714 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 461 511 0.00870035 -3.16357 -0.135112 0.0485771 -0.00968329 0.0032561 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 511 512 3.88996 -0.0281958 -0.276218 0.00295617 0.0613643 0.0912502 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 462 512 0.122157 -3.09977 0.0239496 0.0770165 -0.000713433 -1.41527e-05 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 512 513 3.83797 0.0297327 -0.179258 0.0122462 0.0919223 0.0463176 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 463 513 -0.113572 -3.0456 -0.172146 0.0449117 0.0119165 0.0456888 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 513 514 3.71781 0.170462 -0.223852 0.00158274 0.0873435 0.0611164 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 464 514 0.0424182 -3.164 -0.146429 0.0450361 0.0205531 0.0636576 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 514 515 3.89482 0.0222389 0.0105008 -0.00288901 0.0655682 0.0710208 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 465 515 0.0409562 -3.13976 -0.0892642 0.0590593 -0.014298 0.0976616 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 515 516 3.95329 0.0473616 -0.10755 -0.00445798 0.0862988 0.123392 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 466 516 -0.164743 -3.22428 -0.0865446 0.0735216 0.00238483 0.0270441 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 516 517 3.97917 0.0879153 -0.191707 -0.00372869 0.0939442 0.115294 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 467 517 0.054379 -3.11355 -0.19167 0.0716972 0.0105228 -3.59251e-05 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 517 518 4.00829 0.0957642 -0.284959 0.0169499 0.0813068 0.0313315 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 468 518 -0.106701 -3.09214 -0.220984 0.0659333 0.00377642 0.00775913 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 518 519 3.92345 0.0291007 -0.158137 0.0124476 0.0908164 0.110767 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 469 519 0.107002 -2.95947 -0.139402 0.0620113 0.0044476 0.0549781 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 519 520 3.87629 0.0684311 -0.0609025 0.00993632 0.0734299 0.0877509 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 470 520 -0.108656 -3.03903 0.083943 0.0545671 0.0124822 0.0120321 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 520 521 3.87616 0.165536 -0.111575 0.00530646 0.0659726 0.154374 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 471 521 -0.0784969 -2.83155 -0.0241067 0.0606587 -0.0144503 0.062287 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 521 522 3.93336 0.138194 -0.0748747 0.00176335 0.101838 0.167977 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 472 522 0.0114856 -3.00226 -0.0845597 0.0685469 -0.0164081 0.0381552 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 522 523 3.95375 -0.0797769 -0.20141 -0.00535917 0.0798415 0.0484603 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 473 523 -0.0513233 -2.92298 -0.0297458 0.0585826 -0.00928159 -0.04187 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 523 524 3.88044 0.232017 -0.0105122 -0.00432516 0.0799176 0.108934 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 474 524 0.0427063 -2.96872 -0.100256 0.0789954 0.021286 -0.00420237 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 524 525 3.95145 0.0683336 -0.0597149 0.0143596 0.0838335 0.0941658 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 475 525 -0.0549014 -3.09318 -0.0342945 0.0490925 -0.0104972 0.0182039 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 525 526 3.80783 0.177405 -0.0379598 0.0146907 0.0729651 0.0696751 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 476 526 0.0680504 -2.99512 -0.101228 0.0688634 0.00518964 0.0184658 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 526 527 3.87202 0.222751 -0.107692 0.000693948 0.087039 0.154982 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 477 527 -0.122992 -3.14268 -0.311588 0.0700966 0.00631231 -0.0473039 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 527 528 3.95992 0.153623 -0.202136 0.00814916 0.0694172 0.027455 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 478 528 -0.0623314 -2.95136 0.167926 0.0730348 -0.001431 -0.0477075 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 528 529 3.94116 0.18508 0.0194119 -0.0142119 0.0838081 0.0594661 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 479 529 -0.110363 -3.09787 0.00308389 0.0556246 0.00425071 0.0180718 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 529 530 4.16337 0.296778 -0.180989 0.00145806 0.0942497 0.0540158 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 480 530 -0.171417 -3.10396 -0.143155 0.0812484 -0.0075318 -0.0341758 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 530 531 3.98305 0.0858175 -0.0788322 0.00500794 0.0753316 0.0629777 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 481 531 0.00744409 -3.19463 0.116307 0.0444314 0.00388385 -0.00893924 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 531 532 4.07791 0.104417 -0.0402646 -0.00618066 0.0742438 0.106636 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 482 532 0.0172885 -3.07817 -0.0402404 0.0556358 -0.00105077 -0.0129042 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 532 533 4.16867 0.29963 -0.149733 -0.00275708 0.0670716 0.125705 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 483 533 0.0944517 -3.24257 -0.130989 0.0662688 0.011916 -0.0310471 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 533 534 4.06409 0.189856 0.00061951 0.00689985 0.0925781 0.155153 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 484 534 0.140157 -3.06507 -0.0512154 0.0562917 0.0091265 -0.0478581 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 534 535 3.92174 0.2644 -0.079848 -0.00500359 0.0833138 0.0557615 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 485 535 0.0622585 -3.03014 -0.0791398 0.0750876 0.0082449 -0.0455365 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 535 536 3.98814 0.115147 -0.186112 0.0101489 0.0839566 0.135988 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 486 536 0.0850827 -3.07701 -0.109627 0.0644013 -0.001719 -0.0590063 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 536 537 3.84776 0.0917744 -0.141178 0.00202551 0.0764908 0.0863808 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 487 537 -0.174879 -3.11156 -0.0305111 0.0620026 -0.00486258 -0.0279257 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 537 538 4.11214 0.057549 -0.346564 0.00483302 0.062109 0.056964 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 488 538 -0.0598301 -2.9678 -0.203583 0.0565507 0.0226589 0.0526871 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 538 539 3.9898 -0.0804338 -0.225186 0.00364604 0.0870435 0.063733 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 489 539 -0.136908 -3.23325 -0.0968695 0.0528514 -0.0106577 -0.0341014 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 539 540 4.0618 0.0327376 -0.126014 -0.00978959 0.0869334 0.148875 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 490 540 0.0183003 -3.15107 -0.0892686 0.0518073 -0.0139294 0.0479056 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 540 541 4.0698 0.119983 -0.067476 0.0106398 0.0926672 0.123709 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 491 541 0.144867 -3.06526 -0.156464 0.0435905 -0.0172536 -0.0105708 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 541 542 4.14792 0.120745 0.10754 -0.0200338 0.0882109 0.0827413 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 492 542 0.0404083 -2.82931 0.0840477 0.0639405 -0.0115791 0.0347076 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 542 543 4.09568 -0.0551356 -0.0582114 0.00127462 0.0780678 0.134079 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 493 543 -0.215644 -2.96754 -0.125685 0.0589795 0.00998454 -0.0443006 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 543 544 4.08339 0.135212 -0.0655433 -0.00880676 0.0702492 0.0763876 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 494 544 0.257973 -3.25769 -0.0483693 0.0658216 -0.00802967 0.0863524 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 544 545 4.0795 0.0328024 -0.0783405 -0.00366906 0.0733206 0.0711361 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 495 545 0.158184 -2.9657 -0.109624 0.0684312 -0.00530189 0.0601699 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 545 546 3.93024 0.105637 -0.0186476 0.00191596 0.0713991 0.094287 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 496 546 -0.0478889 -3.20087 -0.0707272 0.07427 0.000812378 0.0181383 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 546 547 3.98135 0.127568 -0.144685 0.00726214 0.0880063 0.056445 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 497 547 -0.0394371 -3.09159 -0.175059 0.0569448 0.00200361 -0.00607273 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 547 548 4.19208 -0.101253 -0.316889 -0.00601598 0.0877118 0.151029 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 498 548 -0.00543063 -3.10341 -0.177335 0.0755875 -0.00873274 -0.00851482 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 548 549 4.14219 0.303988 0.0285385 0.0081434 0.0806931 0.119864 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 499 549 0.158279 -2.95606 -0.0763056 0.0595573 0.00912355 0.0454654 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 549 550 4.14084 0.123261 0.0149417 0.0191959 0.0817442 0.0320899 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 500 550 -0.163621 -3.16965 0.0545318 0.0659283 0.0130754 -0.0151886 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 550 551 4.2856 0.132956 -0.18382 0.00392179 0.0874209 0.0775827 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 501 551 -0.104354 -3.21142 -0.0373729 0.0620785 0.00287161 0.04368 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 551 552 3.95876 0.130382 -0.147787 0.0190924 0.0735096 0.0743083 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 502 552 0.0419734 -3.15903 -0.0196529 0.0572659 -0.00629986 -0.0473105 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 552 553 4.15462 0.207674 0.0782872 0.00413373 0.0899008 0.133173 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 503 553 0.102133 -2.97393 -0.12117 0.0730434 0.0208993 0.00503202 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 553 554 4.03899 0.195841 -0.22051 0.010788 0.0844967 0.102643 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 504 554 -0.0251412 -3.15216 -0.0474008 0.0595686 0.00111218 -0.0393948 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 554 555 4.33492 0.0454974 -0.412621 0.000461212 0.104188 0.0516918 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 505 555 -0.00332317 -3.05428 -0.0346111 0.0617502 0.0188119 -0.0374979 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 555 556 4.14312 -0.0246469 -0.110072 -0.000282772 0.0688482 0.0589417 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 506 556 -0.0533068 -3.13507 -0.0539043 0.0549669 0.00561657 0.00112993 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 556 557 4.08848 0.269272 -0.264466 0.0103545 0.0731958 0.0720859 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 507 557 0.0683012 -3.15511 0.054601 0.0718749 0.0130784 -0.00276691 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 557 558 4.21301 0.228984 -0.211934 0.00401038 0.0888661 0.0506419 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 508 558 -0.150612 -3.02293 -0.024401 0.0679468 0.00516331 -0.0627376 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 558 559 4.08028 0.122719 -0.00964286 0.00839008 0.111177 0.121302 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 509 559 0.129548 -3.07578 -0.213948 0.0643898 -0.0129508 0.0163419 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 559 560 4.13282 0.0802045 -0.206804 0.019373 0.103119 0.0328415 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 510 560 0.115483 -3.05728 -0.133386 0.0654732 -0.0111095 -0.0754246 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 560 561 4.27962 0.0680338 -0.167726 -0.0149808 0.0874889 0.127181 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 511 561 -0.164549 -3.1017 -0.0506549 0.0657427 0.0115839 0.003209 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 561 562 4.13902 0.151543 -0.0770345 0.00259444 0.083451 0.093259 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 512 562 0.0121592 -3.07021 -0.0297745 0.0826955 -0.00731092 -0.00623018 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 562 563 4.1572 0.0191463 -0.333908 0.00316001 0.0973112 0.0700092 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 513 563 0.00163415 -3.14105 -0.165022 0.0646058 0.00494038 -0.00206431 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 563 564 4.00573 0.225083 -0.2103 -0.0163633 0.0903101 0.094936 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 514 564 -0.0918992 -3.21551 -0.0462589 0.0808105 -0.0200222 0.00698442 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 564 565 4.23684 0.0345225 -0.189857 0.0207427 0.0710984 0.118987 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 515 565 -0.00941106 -2.9553 0.0309539 0.0647967 0.00530812 -0.00774183 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 565 566 4.11766 0.0936709 -0.244863 0.00602986 0.0787818 0.0647949 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 516 566 0.0881701 -3.16325 -0.0750626 0.0712499 0.0127565 0.00993766 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 566 567 4.09546 0.171931 -0.290686 0.00579386 0.0756382 0.0597698 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 517 567 0.117849 -2.80609 -0.232063 0.0708833 0.0281805 -0.0155169 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 567 568 4.33513 0.0646891 -0.345993 0.00742182 0.0910747 0.116173 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 518 568 0.137367 -2.90154 -0.0226107 0.0546203 0.0107624 -0.0699045 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 568 569 4.31873 0.0483286 -0.177583 0.0249496 0.10265 0.131922 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 519 569 0.15282 -2.9799 -0.0173958 0.0387413 0.00586395 -0.00137159 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 569 570 4.16762 0.139206 -0.208122 0.0177862 0.0887795 0.0473907 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 520 570 -0.169751 -2.95091 -0.182311 0.0531366 -0.0071244 -0.043167 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 570 571 4.1774 0.100141 -0.270994 -0.0056551 0.0743315 0.10291 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 521 571 0.118028 -3.16972 -0.00385608 0.0544589 -0.00237523 0.0404745 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 571 572 4.21111 0.028043 -0.214451 -0.000724635 0.0788917 0.0865979 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 522 572 0.0744819 -3.06681 -0.10571 0.0523037 0.0115457 0.0297215 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 572 573 3.97529 0.0323595 -0.266289 0.00754517 0.0762605 0.047991 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 523 573 -0.173998 -2.97492 -0.0652306 0.0536759 -0.000476282 0.0543073 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 573 574 4.2122 0.0110234 -0.169995 -0.0116139 0.0825434 0.126044 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 524 574 -0.123564 -2.85526 -0.0244972 0.0592113 0.00188334 -0.038221 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 574 575 4.52554 0.0814973 -0.218838 0.00440094 0.0707324 0.0872324 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 525 575 0.0111203 -3.13927 -0.125059 0.0518476 0.00430814 -0.0149984 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 575 576 4.20093 0.178484 -0.153546 0.0193646 0.0929959 0.0672811 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 526 576 -0.255423 -2.9201 -0.196621 0.0525716 0.0109868 -0.0708919 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 576 577 4.45554 0.134722 -0.293898 0.0145586 0.0855079 0.096924 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 527 577 -0.0583655 -3.09565 -0.0726507 0.0628596 -0.00247638 0.0197565 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 577 578 4.49419 0.0859528 -0.176432 0.0210922 0.0746585 0.0779077 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 528 578 0.0365176 -3.12017 0.0846079 0.0631303 0.00553076 0.023496 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 578 579 4.29297 0.133856 -0.289144 -0.00498905 0.0843463 -0.00076648 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 529 579 0.0365424 -3.01631 -0.181254 0.0521487 0.00696544 -0.070675 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 579 580 4.09957 -0.0325063 -0.161072 0.0158663 0.0793271 0.110988 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 530 580 0.0981233 -3.08102 -0.226484 0.0749365 0.0025697 0.0096942 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 580 581 4.53389 0.226595 -0.133671 0.0149898 0.0902461 0.0710543 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 531 581 0.123115 -3.10015 -0.403189 0.0652793 0.00918251 -0.0460467 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 581 582 4.27189 0.238078 -0.126906 0.0125389 0.0977546 0.0870196 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 532 582 -0.0367158 -2.95233 -0.152982 0.0714582 -0.000864546 -0.0237354 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 582 583 4.23315 0.245158 -0.226537 0.0195492 0.097047 0.140917 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 533 583 0.0902465 -3.11587 -0.178165 0.0649509 0.00203572 -0.0393786 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 583 584 4.25792 0.192358 -0.285872 0.0236409 0.0975044 0.0781299 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 534 584 0.0440548 -2.96893 -0.0821 0.0601803 0.00307157 0.0405787 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 584 585 4.35623 0.165366 -0.264653 0.00360205 0.0906646 0.0910438 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 535 585 -0.143013 -2.9968 -0.0868078 0.067938 0.00776744 -0.0100572 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 585 586 4.46245 0.192824 -0.199804 -0.0157825 0.0971969 0.144557 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 536 586 -0.0114761 -3.03959 0.00187525 0.0728051 -0.000103808 -0.0677429 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 586 587 4.39104 0.119623 -0.0441801 0.0171875 0.0745751 0.0431043 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 537 587 0.0941817 -3.30746 -0.0836066 0.0609027 0.00374263 0.0555212 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 587 588 4.27077 0.0866119 -0.193441 0.0184127 0.0897319 0.101872 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 538 588 -0.0647356 -3.06441 -0.189473 0.082692 0.00873622 -0.0362541 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 588 589 4.31423 0.0100555 -0.00976918 -0.00254526 0.0880652 0.0691444 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 539 589 -0.111086 -2.93712 -0.0480663 0.063339 -0.00507121 -0.0057921 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 589 590 4.15984 -0.00327917 -0.0570958 0.0160054 0.0768483 0.0933413 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 540 590 0.174395 -2.91901 -0.381083 0.0555307 -0.0146265 0.034813 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 590 591 4.08242 0.195928 -0.249705 0.0293336 0.104667 0.175302 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 541 591 0.0193627 -3.01033 -0.196237 0.0591627 0.0134977 0.0896685 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 591 592 4.34058 0.289463 -0.236897 0.00757568 0.0792726 0.106466 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 542 592 0.0930682 -2.9934 -0.291053 0.0721574 -0.0089411 -0.0290288 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 592 593 4.19862 0.27484 -0.343434 0.0201772 0.10111 0.0462058 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 543 593 -0.133796 -3.14294 0.109997 0.0556209 0.0169792 0.00969205 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 593 594 4.31115 0.106374 -0.105547 0.00338607 0.0947796 0.122571 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 544 594 0.0323602 -3.15931 -0.052984 0.0623382 -0.0111761 -0.0195102 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 594 595 4.32924 0.0533522 -0.266254 -0.000194612 0.0833887 0.102272 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 545 595 0.121139 -3.06999 -0.154193 0.05892 -0.0114917 -0.023365 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 595 596 4.24461 0.0746417 -0.0334534 0.00128484 0.0880958 0.0712577 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 546 596 0.0248243 -3.05119 -0.120918 0.0735632 -0.00226406 0.000988924 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 596 597 4.33841 0.498751 0.0540982 0.0191623 0.103731 0.0968355 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 547 597 -0.0769754 -3.19866 -0.306113 0.0623925 0.0150405 0.00700658 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 597 598 4.49115 0.110355 -0.119654 0.00718546 0.0903655 0.0729678 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 548 598 0.0275225 -3.1356 0.0673245 0.0562348 0.0124765 0.00491015 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 598 599 4.50303 -0.0453035 0.00094901 0.0175725 0.0965551 0.0792973 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 549 599 -0.0222005 -3.05045 -0.216093 0.0588531 -0.0180662 0.0567825 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 599 600 4.48083 0.313245 -0.371852 0.0181941 0.0895536 0.0697882 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 550 600 -0.0913171 -3.07627 -0.227804 0.0614361 0.0112592 0.034566 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 600 601 4.37029 0.0298635 -0.182147 -0.00411168 0.105197 0.0687257 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 551 601 0.217781 -3.08133 -0.0219625 0.0602339 0.0024877 0.0449566 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 601 602 4.29162 0.279554 -0.242674 -0.00953771 0.101397 0.0817215 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 552 602 0.138177 -2.98575 -0.21377 0.0701632 -0.0208669 -0.0432925 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 602 603 4.32291 0.10136 -0.182155 0.017475 0.0965541 0.136022 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 553 603 0.105881 -3.09497 -0.225522 0.0500544 0.000549661 -0.0255553 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 603 604 4.57205 0.00141839 -0.115226 0.0237602 0.072418 0.0695433 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 554 604 0.0383596 -3.06322 -0.0970011 0.0688265 -0.00782867 -0.0237748 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 604 605 4.31508 0.115225 -0.287968 0.0225182 0.0793418 0.102334 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 555 605 -0.0493043 -3.06466 -0.00136487 0.0742192 0.00912396 0.00193998 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 605 606 4.47606 0.0393742 -0.258725 -0.0144144 0.088022 0.124299 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 556 606 0.0645644 -2.97867 -0.150372 0.0551866 -0.00887039 -0.067846 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 606 607 4.3798 0.174756 -0.324664 -0.00269858 0.0906761 0.153474 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 557 607 0.0085063 -2.88327 -0.245031 0.0749656 0.000652253 -0.0220066 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 607 608 4.45626 0.334622 -0.174912 0.0134196 0.102041 0.109118 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 558 608 -0.117246 -3.1119 -0.127917 0.0591194 -0.0039858 0.0340398 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 608 609 4.51434 0.222591 -0.174641 0.019614 0.089533 0.109305 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 559 609 -0.0263756 -3.24024 -0.16108 0.0691611 -0.00877491 -0.00945361 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 609 610 4.44196 0.124978 -0.155572 0.0115446 0.0881469 0.0889334 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 560 610 0.167257 -3.23493 -0.0561997 0.0800341 -0.0125998 0.0266861 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 610 611 4.43806 0.145389 -0.227869 0.00627523 0.0986787 0.0593833 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 561 611 -0.130666 -3.12044 -0.359361 0.0602523 0.00832909 0.0446015 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 611 612 4.45431 -0.0354811 -0.177062 0.00591113 0.0967784 0.0359976 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 562 612 -0.0075968 -2.98718 0.0539465 0.0650847 -0.00268539 0.0451599 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 612 613 4.5437 0.219906 -0.195187 0.00452443 0.106376 0.0708472 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 563 613 -0.0297144 -3.02826 -0.0633629 0.061842 0.00307799 0.0274596 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 613 614 4.40734 0.262372 -0.324841 -0.00395617 0.0800662 0.080889 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 564 614 -0.0219157 -3.08952 0.0546854 0.0648266 -0.017525 -0.0414769 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 614 615 4.38916 0.11042 -0.151074 -0.00552542 0.0745524 0.122006 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 565 615 -0.180138 -2.92808 -0.146498 0.0697574 0.015307 0.0126191 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 615 616 4.35209 0.0124038 -0.172293 -0.000650352 0.0967829 0.101845 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 566 616 -0.0209347 -3.13195 -0.0894558 0.0671641 0.00742254 -0.0981321 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 616 617 4.42599 0.171881 -0.135108 -0.00890943 0.0647961 0.0611661 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 567 617 0.103565 -2.87903 -0.0553424 0.0632051 0.00247305 0.0240435 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 617 618 4.61995 0.282469 -0.162463 0.000609223 0.0952048 0.0118725 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 568 618 0.0717569 -3.03175 -0.147548 0.0551176 -0.00692343 0.00524318 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 618 619 4.49564 0.227836 -0.0659887 0.00110848 0.0813638 0.0455096 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 569 619 0.176132 -3.03593 -0.226181 0.0712884 -0.00166718 -0.00768827 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 619 620 4.43863 0.344181 -0.209121 0.00346999 0.0829503 0.0170208 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 570 620 0.0262121 -3.2364 -0.31317 0.0618361 -0.000765218 0.0192015 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 620 621 4.39079 0.243594 -0.142127 0.00308221 0.0994166 0.101129 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 571 621 -0.0771407 -3.21892 -0.143892 0.0551687 -0.00892679 -0.0431961 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 621 622 4.38629 0.127724 -0.109179 0.0110774 0.103313 0.0777007 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 572 622 -0.0191508 -2.89773 -0.192926 0.0551379 -0.00276794 -0.0876222 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 622 623 4.318 0.166077 0.0118998 -0.0091904 0.112464 0.140886 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 573 623 0.115673 -2.9967 -0.184285 0.0725852 0.00775889 0.0703655 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 623 624 4.46395 0.299958 0.0533495 0.00154629 0.0859621 0.104486 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 574 624 -0.0805158 -3.0637 -0.0155647 0.0532142 0.00222468 -0.00334276 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 624 625 4.55022 0.0422739 -0.0393174 -0.00941836 0.0900885 0.101733 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 575 625 -0.149993 -3.03048 -0.0277595 0.065365 0.00717818 0.0387678 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 625 626 4.60777 0.170551 -0.294149 0.0094881 0.0768213 0.117291 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 576 626 0.116528 -3.22838 -0.0339172 0.0584637 0.00383351 0.0103322 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 626 627 4.58635 0.0437147 -0.247564 0.00345608 0.1075 0.12136 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 577 627 -0.110781 -3.10471 -0.199706 0.0682467 0.00170832 0.0806603 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 627 628 4.56696 0.121635 -0.0161831 -0.0115688 0.0859945 0.123461 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 578 628 0.00109741 -3.14353 -0.105799 0.0616737 -0.0112345 -0.00630755 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 628 629 4.58803 0.231626 -0.137042 -0.00895203 0.0828832 0.0453989 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 579 629 0.0974902 -3.11791 -0.131678 0.0583319 -0.0051011 -0.0723996 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 629 630 4.69801 0.123747 -0.334257 -0.0140901 0.080342 0.0610762 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 580 630 0.00453313 -2.9714 0.0925819 0.0557266 0.00532714 0.0275552 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 630 631 4.58682 0.0279869 -0.174891 0.0123522 0.0798607 0.0458531 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 581 631 -0.115355 -2.98364 0.157234 0.062758 -0.00972008 0.0418193 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 631 632 4.43235 0.257981 -0.246344 -0.0203994 0.101156 0.123704 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 582 632 0.132042 -3.11403 -0.0589675 0.0685233 -0.0107664 -0.0571613 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 632 633 4.67311 0.342888 -0.255237 -0.00415209 0.080697 0.0811915 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 583 633 -0.0531079 -3.28654 -0.178329 0.0517913 0.0161975 -0.0490589 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 633 634 4.70961 0.101084 -0.302912 -0.00379722 0.0752333 0.0690831 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 584 634 -0.102543 -2.91659 -0.169003 0.0490259 -0.010582 -0.00404935 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 634 635 4.5897 0.252222 -0.198263 0.00337098 0.0868275 0.061946 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 585 635 0.0188628 -3.08291 -0.0545405 0.0567148 -0.00985038 -0.0124196 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 635 636 4.51069 0.200092 -0.303932 -0.00223501 0.0911032 0.0438181 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 586 636 -0.0186219 -2.91079 -0.169436 0.0649621 0.00858233 -0.107501 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 636 637 4.69478 0.255173 -0.0433796 0.00363234 0.0969772 0.103413 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 587 637 0.163032 -2.88887 -0.20214 0.0678423 0.0102075 -0.0248551 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 637 638 4.58338 0.0998904 -0.327242 -0.00232782 0.0917768 0.0803202 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 588 638 -0.0349211 -2.90975 -0.0629346 0.0547944 0.00492398 0.016901 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 638 639 4.52351 0.0892914 -0.0622867 0.0269003 0.0947183 0.111687 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 589 639 -0.0784669 -2.92389 0.048557 0.0649188 -0.00841817 0.0468179 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 639 640 4.53851 0.151947 -0.268693 0.00450729 0.106453 0.00778613 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 590 640 -0.0971855 -3.25658 -0.121232 0.0561153 0.00448277 -0.0340979 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 640 641 4.61971 0.236515 -0.218548 -0.00665171 0.0870592 0.0661211 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 591 641 -0.0338137 -3.10458 -0.0901958 0.0490569 0.00192585 -0.0352977 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 641 642 4.58013 0.130569 -0.0589895 -0.00800215 0.0962558 0.160234 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 592 642 0.0211381 -3.10805 0.117471 0.0504094 0.0122607 0.00332331 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 642 643 4.5533 8.58184e-06 -0.145173 0.010368 0.0931664 0.0691247 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 593 643 -0.0390567 -2.88846 -0.0667041 0.0654715 0.000640355 -0.00159488 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 643 644 4.56742 0.318652 -0.223275 0.00055354 0.0923862 0.120507 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 594 644 -0.0688095 -2.9161 -0.064569 0.0536461 -0.00677999 -0.0678712 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 644 645 4.69144 0.086352 -0.252866 0.00713131 0.0964524 0.0958729 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 595 645 0.104472 -3.12484 -0.116632 0.0616614 -0.00136236 0.0398051 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 645 646 4.47829 0.286719 -0.328534 -0.00268613 0.105356 0.0631085 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 596 646 -0.0754471 -3.10779 -0.122706 0.0585459 0.0018651 -0.0621258 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 646 647 4.5677 0.304649 -0.263829 0.000226583 0.0889639 0.0266707 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 597 647 -0.293249 -3.21274 -0.103374 0.0516183 0.000753764 -0.00369899 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 647 648 4.61671 0.135063 -0.248071 -0.00991093 0.0934847 0.114669 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 598 648 -0.0803516 -3.08883 -0.0913335 0.0715421 -0.01484 -0.0131632 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 648 649 4.59082 -0.0719269 -0.282693 0.00415818 0.0880186 0.137642 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 599 649 0.135486 -3.16659 0.0217741 0.0709937 0.0129039 -0.0738981 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 649 650 4.59289 0.202558 -0.197916 0.0120858 0.091541 0.0879692 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 600 650 -0.034966 -3.0843 -0.0254212 0.0657932 3.44249e-06 -0.0428018 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 650 651 4.6122 0.311188 -0.346963 -0.000633006 0.0964039 0.106399 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 601 651 -0.0783863 -2.89001 -0.088552 0.052777 -0.00435127 -0.00922282 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 651 652 4.58803 0.210786 -0.337134 -0.00809259 0.0931546 0.0775802 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 602 652 0.0286726 -3.02008 -0.0385886 0.0513643 -0.00266806 0.0464828 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 652 653 4.63035 0.0195722 -0.322998 -0.000505567 0.103379 0.103236 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 603 653 0.0625562 -3.10728 -0.0534136 0.0605436 -0.00902888 -0.00962723 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 653 654 4.64071 -0.0476349 -0.390215 0.000775472 0.0897673 0.0730786 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 604 654 -0.0726515 -3.11078 -0.0699573 0.0576288 -0.016824 0.0145728 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 654 655 4.49805 0.208642 -0.108222 0.0264607 0.0856655 0.149565 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 605 655 0.111023 -2.91284 -0.167086 0.0349309 0.000675564 -0.0227562 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 655 656 4.99066 0.168336 -0.259591 0.00104361 0.10026 0.0887065 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 606 656 0.0301243 -3.10369 -0.0933881 0.062009 0.0109385 -0.014552 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 656 657 4.59405 0.135321 -0.253109 0.00783487 0.0847765 0.0874815 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 607 657 0.250933 -2.89436 -0.0721453 0.0658007 0.00349657 -0.00166186 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 657 658 4.82022 -0.00036991 -0.219453 0.00250863 0.109499 0.10809 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 608 658 -0.142257 -2.94673 -0.100253 0.0529481 0.00168719 0.0453418 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 658 659 4.69842 0.0679796 -0.276004 7.54776e-05 0.0818596 0.0853074 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 609 659 -0.106918 -3.22448 -0.120135 0.0680987 -0.00060922 0.0120484 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 659 660 4.77755 0.0719081 -0.0206436 0.0124007 0.104744 0.0538124 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 610 660 -0.107243 -3.09151 -0.121869 0.0528376 0.00159081 -0.0506813 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 660 661 4.77593 0.0848698 -0.202075 0.0185212 0.0858977 0.164082 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 611 661 0.0576411 -2.92054 -0.0636224 0.0607549 0.00528018 0.0021466 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 661 662 4.71358 0.0893484 -0.151853 -0.00554666 0.0943674 0.122246 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 612 662 0.080842 -3.10442 -0.0254554 0.0556198 -0.0063859 -0.0113843 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 662 663 4.75095 0.0201234 -0.328919 0.0241477 0.0942646 0.0449238 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 613 663 -0.000810475 -2.91316 -0.22155 0.0585487 -0.0115252 -0.00866135 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 663 664 4.58738 0.117525 -0.069831 0.00870518 0.0853772 0.170112 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 614 664 -0.131808 -2.9568 0.0245631 0.0548007 0.00269959 0.0160802 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 664 665 4.78619 0.0194477 -0.149245 -0.00716306 0.0942794 0.0933988 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 615 665 0.139337 -2.98617 -0.145113 0.0545958 0.00794486 -0.0094797 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 665 666 4.77068 0.138414 -0.16816 -0.00139318 0.0937291 0.0599373 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 616 666 0.0209602 -3.14324 -0.14566 0.0561549 0.00774943 -0.0796565 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 666 667 4.84049 0.248311 -0.17468 0.00795232 0.101196 0.0742189 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 617 667 -0.0323372 -3.03405 -0.00795233 0.0611662 0.00763729 0.00179287 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 667 668 4.8285 0.100505 -0.349505 0.0107263 0.0943786 0.0762927 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 618 668 0.0625432 -2.96391 -0.249299 0.0492326 -0.00482146 0.018272 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 668 669 4.88883 0.14119 -0.46285 0.0108026 0.083383 0.05812 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 619 669 -0.00919857 -3.20073 -0.110496 0.0685864 -0.00867677 0.0797899 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 669 670 4.75482 0.0806364 -0.0462016 0.0122757 0.109008 0.0731757 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 620 670 0.142185 -3.16806 -0.183042 0.0625283 -0.00285848 -0.012259 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 670 671 4.71246 0.175771 -0.371031 -0.00129681 0.110878 0.0838478 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 621 671 -0.0838522 -3.06195 -0.104522 0.0525652 -0.00659028 -0.0842468 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 671 672 4.97834 0.0192568 -0.103205 0.0117431 0.0875083 0.0812011 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 622 672 -0.146327 -3.08104 -0.203005 0.0479553 -0.00266307 0.020203 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 672 673 4.82775 0.142154 -0.256223 0.0151808 0.0981574 0.140873 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 623 673 0.129303 -3.00686 -0.0162339 0.0769462 0.00864174 -0.0396603 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 673 674 4.82017 0.176759 -0.338064 0.00367771 0.104707 0.0637959 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 624 674 -0.120919 -2.88785 -0.0695128 0.0646997 0.00110876 -0.0121386 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 674 675 4.9748 0.27584 -0.316333 0.00762002 0.0966097 0.130372 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 625 675 0.108143 -3.22631 -0.0574474 0.0562434 -0.00145129 -0.0311135 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 675 676 4.61906 0.20413 -0.273103 0.00422076 0.0913695 0.0835297 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 626 676 0.00855134 -3.03155 0.0720902 0.0643427 -0.00230099 0.00408353 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 676 677 4.86599 0.0423888 -0.306918 0.0100479 0.0902857 0.0825479 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 627 677 -0.0407317 -2.99311 -0.0451831 0.0712133 0.0036444 -0.0216028 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 677 678 4.93698 0.26028 -0.2249 -0.00220309 0.0906377 0.0549771 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 628 678 0.153689 -3.03586 -0.119724 0.0684265 0.00762086 -0.0201499 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 678 679 4.73583 0.13002 -0.312245 -0.00537247 0.0850064 0.0723021 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 629 679 -0.0667627 -3.17025 -0.0865129 0.0393907 -0.00128729 0.00811489 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 679 680 4.86816 0.0790258 -0.165199 0.0123455 0.097114 0.065086 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 630 680 0.240884 -2.94906 -0.146747 0.0512329 0.000560319 -0.0705929 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 680 681 4.89984 0.228714 -0.238236 0.0001698 0.0974527 0.104206 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 631 681 -0.0322977 -3.11386 -0.256465 0.0600328 0.00703726 -0.0155486 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 681 682 4.82551 0.128119 -0.207736 0.0112305 0.0916274 0.0641891 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 632 682 0.0458059 -3.10663 -0.230961 0.054357 0.00603689 0.0183501 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 682 683 4.80184 0.00748369 -0.0880933 -0.00360608 0.0881013 0.123437 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 633 683 0.105267 -3.06434 -0.0411372 0.0503826 -0.00677093 -0.0558923 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 683 684 4.97453 0.156508 -0.317605 0.0053586 0.0978108 0.163665 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 634 684 0.0417394 -2.95678 -0.00337082 0.0483179 0.0124118 0.0394632 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 684 685 4.80416 0.100665 -0.078458 0.0121502 0.105107 0.0227515 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 635 685 0.100183 -3.00557 -0.0809461 0.0610304 -0.0183025 -0.00347699 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 685 686 4.91193 0.0590685 -0.250704 -0.00173355 0.102507 0.0405014 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 636 686 0.0405188 -2.94075 -0.0807655 0.0442812 0.00892195 0.0306478 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 686 687 4.72536 0.254034 -0.280541 0.00922299 0.0977044 0.122585 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 637 687 0.0948729 -3.1515 -0.0340898 0.0600422 0.0100612 0.0159968 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 687 688 4.75524 0.229598 -0.219658 0.00497092 0.0988943 0.065752 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 638 688 -0.0413858 -3.18189 -0.024737 0.055668 0.000888519 0.0246513 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 688 689 4.9573 0.231367 -0.269147 0.0284867 0.103992 0.170789 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 639 689 0.116434 -3.10073 -0.158501 0.0593271 -0.0159908 0.00912532 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 689 690 4.77554 0.273571 -0.0551941 -0.00636443 0.0760468 0.0520727 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 640 690 0.0824377 -3.11335 -0.148959 0.0582237 -0.0101342 0.0423113 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 690 691 4.88762 0.0357302 -0.223774 0.00848941 0.103085 0.0840575 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 641 691 -0.104628 -3.00161 -0.103736 0.0635966 -0.0171134 -0.029571 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 691 692 4.81846 0.145556 -0.237586 0.00539458 0.0910077 0.0717718 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 642 692 -0.0255222 -3.10173 0.0753851 0.040855 -0.0190997 0.0485578 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 692 693 4.9306 0.16921 -0.199292 -0.0168024 0.0997127 0.0869785 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 643 693 0.134381 -2.95403 -0.107628 0.0715033 -0.00426043 0.0236282 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 693 694 4.84945 0.253784 -0.235495 0.0175242 0.0953525 0.0539144 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 644 694 -0.0927595 -3.01516 -0.0966376 0.0605483 -0.00666778 0.0137219 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 694 695 4.74567 0.176565 -0.0688786 0.00102781 0.0832532 0.139511 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 645 695 0.0650283 -3.09518 0.00256764 0.0707439 0.00543479 0.0205599 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 695 696 4.72455 0.182174 -0.351116 -0.0104963 0.106076 0.040436 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 646 696 0.06834 -3.10697 -0.0879081 0.0651332 0.00683409 0.00528532 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 696 697 4.79913 0.104392 -0.298193 0.00656325 0.0982445 0.0645916 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 647 697 -0.104393 -3.08199 -0.114826 0.0646953 0.0100784 -0.0466152 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 697 698 4.9526 -0.0545478 -0.158798 0.00162925 0.120881 0.0967649 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 648 698 -0.138608 -2.95232 -0.11823 0.0568332 -0.00746389 -0.0268482 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 698 699 4.82726 0.436867 -0.0359374 0.00183485 0.100675 0.0362665 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 649 699 -0.257695 -2.99525 -0.149945 0.0463249 0.00945625 -0.0238801 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 699 700 4.94314 0.14087 -0.139945 -0.00556348 0.083005 0.0493162 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 650 700 -0.0894419 -3.19973 0.0132695 0.0714461 0.00213881 -0.0250355 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 700 701 5.04451 0.244174 -0.161839 0.0157913 0.0954645 0.0721594 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 651 701 -0.0248016 -2.97752 -0.110349 0.0705567 0.0257843 0.00494596 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 701 702 4.84351 0.105472 -0.29265 -0.00615854 0.0833187 0.102861 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 652 702 0.0620787 -3.20143 -0.312803 0.0553836 -0.0145885 0.0203886 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 702 703 4.92655 0.161364 -0.0337247 -0.00695027 0.102421 0.0186239 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 653 703 0.0826487 -3.06463 0.0273676 0.0615081 -0.0135372 -0.0268066 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 703 704 4.92279 0.129379 -0.302255 0.0117016 0.114484 0.127468 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 654 704 -0.0814438 -3.13962 -0.148475 0.056607 -0.0119339 -0.00497065 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 704 705 4.8111 0.245733 -0.30226 0.00508755 0.0907482 0.090034 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 655 705 0.0662315 -3.07415 -0.103446 0.0535861 0.010794 0.00358945 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 705 706 5.0641 0.15892 -0.225412 0.0105472 0.0907386 0.0616333 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 656 706 -0.000459968 -3.02377 -0.110942 0.0699077 0.00844676 -0.0478905 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 706 707 4.80976 0.157741 -0.169973 -0.00686053 0.103871 0.0693185 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 657 707 0.0770635 -2.9474 -0.049141 0.0593674 0.00457421 0.0324447 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 707 708 4.8845 0.108034 -0.261472 0.0195029 0.0944785 0.148876 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 658 708 -0.0495085 -3.27615 -0.147046 0.0621023 0.00396419 0.0550467 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 708 709 4.80948 0.262969 -0.0422534 0.011107 0.0984069 0.0897239 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 659 709 0.0033146 -2.96458 -0.00803129 0.0625363 -0.00361804 -0.0223613 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 709 710 4.88789 0.0453553 -0.263956 -0.00325074 0.0868413 0.0909004 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 660 710 0.243191 -3.20723 -0.0870602 0.0723569 -0.000358629 -0.0549854 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 710 711 4.96909 0.0945721 -0.235013 0.00877381 0.0933477 0.0913585 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 661 711 0.204564 -3.00899 -0.185351 0.070743 -0.00195415 0.0411016 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 711 712 4.957 0.20409 -0.166317 -0.00513373 0.115013 -0.00219833 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 662 712 -0.0463396 -2.9789 -0.0567237 0.0649891 0.0106183 -0.0136026 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 712 713 4.82769 -0.0779356 -0.0859007 0.00286543 0.111851 0.0719682 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 663 713 -0.0362462 -3.02737 0.0813519 0.0480504 0.0029693 -0.0409108 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 713 714 4.99237 0.226358 -0.201009 0.0175574 0.0899334 0.0937055 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 664 714 -0.0650279 -2.9986 -0.160333 0.0550692 0.00899256 -0.0263011 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 714 715 4.847 0.185863 -0.273731 -0.00655556 0.11656 0.120036 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 665 715 0.131739 -3.09642 -0.071034 0.076089 0.00550913 0.0278143 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 715 716 4.91373 0.20578 -0.241385 0.0305883 0.100785 0.106056 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 666 716 0.0797012 -2.97075 -0.0576583 0.0738755 -0.00907578 0.0275996 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 716 717 5.03791 0.0643769 -0.223127 -0.00223908 0.0909435 0.116042 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 667 717 -0.00621292 -3.17685 -0.199553 0.0568477 -0.00849604 0.0556099 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 717 718 5.0882 0.286328 -0.308134 0.00395751 0.113028 0.0820751 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 668 718 0.060683 -3.00908 -0.180527 0.0419437 0.00309748 0.0113851 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 718 719 5.13539 0.131652 -0.36562 -0.00721369 0.101202 0.16685 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 669 719 -0.0318945 -3.14906 0.0363823 0.0662179 -0.0046484 0.00147924 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 719 720 5.11758 0.004806 -0.354268 -0.00169348 0.0869805 0.125518 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 670 720 0.178589 -3.10867 0.0191606 0.07398 0.0119983 -0.0277615 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 720 721 5.04158 0.136478 -0.222813 0.00480269 0.0940545 0.125554 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 671 721 -0.0155655 -3.08082 -0.0531484 0.0658749 -0.00664142 -0.0913176 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 721 722 4.94569 0.0317493 -0.155873 -0.00103506 0.11041 0.113469 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 672 722 0.150353 -3.0813 -0.0456873 0.0871214 -0.00183637 0.0234943 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 722 723 4.99568 0.172668 -0.416876 0.0258139 0.101952 0.0717157 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 673 723 0.0097035 -3.05826 -0.0986314 0.0681282 0.0148936 -0.00734021 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 723 724 5.0321 0.0729174 -0.381444 0.00469404 0.084094 0.0323003 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 674 724 -0.0599824 -3.06906 -0.221878 0.0571129 0.00517287 -0.0150848 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 724 725 5.10744 0.304035 -0.365794 0.01609 0.104756 0.150386 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 675 725 0.0611193 -2.84611 -0.118206 0.07331 -0.0147959 -0.000308622 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 725 726 5.23308 0.150503 -0.271173 -0.00547725 0.109904 0.0174743 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 676 726 0.0710463 -2.91241 -0.208907 0.0530331 0.00253356 0.045755 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 726 727 5.00387 -0.0204341 -0.221934 -0.00900423 0.115366 0.108748 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 677 727 0.0518681 -2.99773 -0.150974 0.0589842 0.0122081 0.0233584 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 727 728 4.83586 0.262332 -0.307353 0.00961491 0.0889457 0.109844 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 678 728 -0.225372 -3.01335 -0.0491786 0.0505986 0.00125697 0.0301993 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 728 729 5.13506 0.159915 -0.107686 -0.00318129 0.107694 -0.000191493 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 679 729 -0.012386 -3.14058 -0.147946 0.0613115 -0.00893748 0.0327034 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 729 730 5.14321 0.185646 -0.461683 0.000511147 0.0852827 0.0518702 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 680 730 0.127501 -3.23616 -0.146851 0.0858101 -0.000631745 -0.0425273 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 730 731 5.11076 0.142116 -0.190949 0.0105194 0.103873 0.0524803 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 681 731 -0.0608466 -3.12941 -0.124451 0.0718154 0.00541046 0.0129321 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 731 732 5.00292 0.032622 -0.351662 0.00313734 0.0969511 0.118482 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 682 732 0.0172322 -3.23209 -0.0754052 0.050612 0.00145916 0.071669 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 732 733 5.1493 0.111485 -0.309985 0.00568752 0.108775 0.0793158 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 683 733 -0.159021 -3.05302 0.0570758 0.0796614 -0.00918807 -0.0512263 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 733 734 5.02261 -0.0151599 -0.395022 -0.0107817 0.0958243 0.133202 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 684 734 -0.0431675 -3.03141 -0.165398 0.0645764 -0.00403677 0.0519855 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 734 735 5.08378 0.10967 -0.160555 -0.00247786 0.0940024 0.129468 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 685 735 -0.0694909 -3.00382 0.0168952 0.0518273 -0.0125248 0.0036106 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 735 736 4.96436 0.347592 -0.0562935 0.0198373 0.104835 0.0688686 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 686 736 0.0843335 -3.03308 0.0133178 0.054561 0.0112583 -0.00585566 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 736 737 5.15269 0.240358 -0.326321 -0.000265483 0.0972981 0.0518618 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 687 737 -0.0155025 -3.00305 -0.0920616 0.0434408 -0.0221745 0.00507161 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 737 738 5.13317 0.140882 -0.236203 5.65843e-05 0.114924 0.0837862 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 688 738 -0.0530177 -3.07663 -0.197915 0.0578139 0.00825078 -0.0333102 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 738 739 5.01557 0.123123 -0.408925 0.0102592 0.0962423 0.0528312 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 689 739 -0.03415 -3.04972 -0.0554636 0.0379105 -0.0154694 -0.0283152 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 739 740 5.0204 -0.0823697 -0.284228 -0.00486723 0.103381 0.0115507 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 690 740 -0.123281 -3.04403 -0.230141 0.057816 0.0113993 0.0335845 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 740 741 5.10069 0.104287 -0.153915 0.0053845 0.0999738 0.103005 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 691 741 -0.108546 -2.95644 0.104505 0.0611476 0.00262854 0.0219741 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 741 742 5.0754 -0.013166 -0.118819 0.021454 0.0935835 0.0983873 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 692 742 -0.02648 -2.98653 -0.00950177 0.0555314 -0.0202864 0.0220555 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 742 743 5.04127 0.11027 -0.188268 0.00197452 0.110593 0.0749265 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 693 743 0.136399 -2.98141 -0.0754871 0.0550242 -0.0118737 -0.0300052 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 743 744 5.12915 0.0372705 -0.328298 0.0130503 0.0940853 0.0761804 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 694 744 0.0250219 -3.03039 -0.178337 0.0640917 0.0065361 0.0651105 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 744 745 5.18019 -0.115299 -0.200111 0.0114283 0.110952 0.145932 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 695 745 -0.0317407 -3.02702 -0.00655395 0.041714 0.0138171 -0.0528609 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 745 746 4.96612 0.298684 -0.216537 0.0159545 0.0948664 0.0939178 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 696 746 0.0349984 -3.07044 -0.335171 0.046457 0.00342512 0.0290837 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 746 747 5.03097 -0.0854337 -0.22582 0.0145452 0.105745 0.0696372 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 697 747 0.0869135 -3.03999 -0.0430887 0.0810378 -0.0225104 -0.0463209 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 747 748 5.2337 0.0856714 -0.305334 0.00621032 0.10018 0.170719 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 698 748 0.081417 -3.11205 0.0585525 0.0655414 -0.0121962 0.00284265 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 748 749 5.26509 0.0247955 -0.384943 0.013629 0.0821419 0.0958031 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 699 749 0.0472414 -3.27667 -0.0135453 0.0537665 0.0133011 -0.0344399 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 749 750 5.1928 0.367558 -0.188986 -0.00505421 0.0914533 0.0813406 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 700 750 0.00143124 -3.02074 -0.130756 0.0515915 -0.00649855 -0.0459152 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 750 751 5.25921 0.179427 -0.0422579 -0.000191209 0.102508 0.044356 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 701 751 -0.0646202 -3.13637 -0.221832 0.0754449 -0.0102576 -0.0266814 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 751 752 4.99562 0.0922855 -0.160848 0.0162467 0.104019 0.053426 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 702 752 0.0602422 -3.06527 0.0551907 0.0516273 -0.0138274 -0.0643509 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 752 753 5.15008 -0.209059 -0.275634 0.0148778 0.102075 0.0722559 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 703 753 0.0497318 -3.14818 -0.284565 0.0624102 0.00343305 -0.0627504 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 753 754 4.94842 0.0104051 -0.209326 0.0189345 0.0994756 0.0204951 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 704 754 0.200219 -3.01629 -0.164168 0.0671322 -0.00966129 0.0167748 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 754 755 5.02932 0.076045 -0.171217 0.0110879 0.0964613 0.0799254 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 705 755 -0.052488 -2.81056 -0.262404 0.0747598 -0.00847666 -0.0677819 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 755 756 5.36261 0.0304361 -0.355689 0.00618968 0.102007 0.0748421 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 706 756 0.136117 -3.26935 -0.0411376 0.0698121 -0.0098603 -0.00597304 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 756 757 5.12642 0.00873206 -0.305722 -0.00551368 0.110076 0.023757 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 707 757 -0.0220964 -3.13557 -0.109377 0.0728401 0.00349502 -0.0436676 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 757 758 5.09088 0.0265784 -0.387801 0.000447018 0.103646 0.0744597 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 708 758 0.1715 -2.92704 -0.0953862 0.0579933 0.011182 0.0554201 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 758 759 5.17741 0.185837 -0.246811 0.0112648 0.101432 -0.0292101 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 709 759 -0.0177704 -2.92812 -0.12304 0.0577677 0.00176575 -0.0364849 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 759 760 4.99066 0.0269255 -0.272423 0.00788422 0.117211 0.0892273 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 710 760 -0.00132276 -3.15674 -0.0104801 0.0560096 -0.00410729 0.015905 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 760 761 5.33196 0.0395832 -0.0656167 0.00173319 0.124705 0.0737187 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 711 761 0.232386 -3.19802 -0.0631278 0.0511183 0.0098773 -0.0104103 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 761 762 5.0744 0.139963 -0.525425 0.0150037 0.0808953 0.159698 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 712 762 0.0735347 -3.03618 -0.170271 0.0531005 -0.00717228 -0.0429163 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 762 763 5.05055 0.188472 -0.369217 0.0184699 0.105553 0.0261748 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 713 763 -0.102391 -2.98661 -0.0574297 0.0516266 -0.02512 -0.0303779 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 763 764 5.31834 0.2129 -0.2007 0.0136198 0.0997641 0.136163 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 714 764 0.0790525 -3.07381 0.0923594 0.0434949 -0.0113052 -0.00645312 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 764 765 5.10367 0.0125937 -0.33263 0.00155229 0.113295 0.0488067 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 715 765 -0.246045 -2.94552 -0.0813163 0.0697639 0.0068265 -0.00907065 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 765 766 5.23799 0.046888 -0.332553 0.0159955 0.107376 0.0891476 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 716 766 0.0421949 -3.12307 -0.00169529 0.0742734 -0.00265166 0.0158117 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 766 767 5.11997 0.302825 -0.221093 -0.00158137 0.109389 0.0759755 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 717 767 -0.0764322 -2.9681 -0.186424 0.0566583 0.0152756 0.0377777 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 767 768 5.15075 0.180305 -0.330729 -0.00199442 0.105313 0.0886047 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 718 768 0.145398 -3.18209 -0.0298385 0.0614519 -0.011378 -0.0592105 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 768 769 5.39527 0.0977658 -0.12326 -0.00536426 0.113237 0.0646543 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 719 769 0.228894 -3.07293 -0.122738 0.0718271 -0.0104225 -0.0169696 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 769 770 5.21957 -0.0183566 -0.0775419 -0.0152212 0.110608 0.058591 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 720 770 0.0141565 -3.11093 -0.065615 0.0578667 -0.00623231 -0.00766028 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 770 771 5.11023 0.0165693 -0.360401 -0.00328817 0.0979028 0.0653148 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 721 771 -0.163798 -3.03062 -0.144652 0.0628255 -0.00166916 -0.0263083 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 771 772 5.19766 0.226146 -0.340504 -0.00436364 0.105971 0.0948516 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 722 772 0.00167071 -3.00048 -0.203674 0.0631385 0.0106892 -0.112683 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 772 773 5.22283 0.251145 0.00810585 0.00879955 0.109563 0.074257 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 723 773 -0.0744552 -3.10671 -0.261514 0.0601962 4.57808e-05 -0.0434785 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 773 774 5.08066 0.17895 -0.0709691 0.00320106 0.0918504 0.0537634 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 724 774 -0.0401624 -3.08972 -0.11275 0.0603262 0.00322228 0.0574886 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 774 775 5.2177 0.199758 -0.191193 0.0169965 0.112934 0.0301586 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 725 775 0.0601041 -3.05128 -0.0216824 0.0602345 -0.00999635 -0.0440078 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 775 776 5.26067 0.207537 -0.439405 0.0172082 0.0907427 0.0905976 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 726 776 0.0712137 -3.10376 -0.139921 0.0582393 0.00500706 0.0333057 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 776 777 5.24894 0.103057 -0.373697 -0.0149189 0.108681 -0.015175 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 727 777 0.0553983 -3.0064 -0.0140212 0.043505 0.00360782 -0.0524554 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 777 778 5.26307 0.0661414 -0.149344 0.00157535 0.110997 0.148914 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 728 778 0.10469 -2.94151 -0.0784139 0.0482516 -0.0036051 0.0244932 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 778 779 5.48233 0.00571877 -0.339827 0.00748891 0.107663 0.0845218 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 729 779 0.0935204 -3.05444 0.0383777 0.0595314 0.0119992 -0.0144589 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 779 780 5.23838 0.246089 -0.220833 0.0105228 0.0926641 0.0333228 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 730 780 0.0792262 -2.97175 -0.261219 0.0653545 0.0106858 0.011921 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 780 781 5.32681 0.209297 -0.116294 -0.0157647 0.103939 0.0122542 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 731 781 -0.0647844 -3.19386 0.0147493 0.0772045 -0.0137697 0.0205495 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 781 782 5.31848 0.092892 -0.216081 0.0208823 0.0923527 0.0931964 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 732 782 -0.113585 -3.20825 -0.123464 0.063508 -0.00998247 -0.0624735 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 782 783 5.35902 0.258926 -0.336743 -0.00439501 0.117874 0.140314 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 733 783 -0.0380606 -3.23021 -0.0350393 0.0803182 0.020459 -0.0179491 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 783 784 5.34362 0.0600009 -0.224552 -0.00122531 0.120554 0.103394 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 734 784 -0.0532074 -2.92181 0.0252862 0.0686423 -0.00763397 -0.017811 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 784 785 5.20441 0.285658 -0.247576 -0.0143382 0.0976633 0.0468873 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 735 785 -0.0742974 -2.96135 -0.0917263 0.0702588 -0.0122577 -0.0607646 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 785 786 5.20415 0.160135 -0.371703 0.0197402 0.113456 0.000414329 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 736 786 -0.0594782 -3.04182 0.169928 0.0704612 -0.00872593 -0.0085634 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 786 787 5.41632 0.247935 -0.265075 0.00180537 0.0802425 0.00915503 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 737 787 -0.05792 -2.93917 -0.00708197 0.0672262 0.000110484 0.00434743 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 787 788 5.35646 0.110047 -0.240483 0.00916755 0.106768 0.0771856 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 738 788 -0.048066 -2.97112 -0.122619 0.0539979 0.00678632 0.0203701 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 788 789 5.3763 0.163994 -0.199547 -0.00395076 0.0985334 0.0837336 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 739 789 -0.0804408 -3.06758 -0.195288 0.0577575 0.00147955 -0.013511 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 789 790 5.22384 0.118062 -0.251427 -0.0101278 0.106145 0.0677628 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 740 790 -0.100383 -3.24976 -0.177829 0.0554303 0.0131824 -0.00879511 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 790 791 5.2674 0.163355 -0.181639 -0.00264569 0.119881 0.14238 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 741 791 0.08881 -3.15537 -0.204829 0.0605312 -0.0197986 0.00472212 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 791 792 5.46235 0.112308 -0.294751 0.0270857 0.0955492 0.100532 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 742 792 -0.0426849 -3.00134 0.0248191 0.0436301 -0.00484735 -0.00197588 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 792 793 5.34053 0.143157 -0.288242 0.017041 0.098476 0.0745186 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 743 793 0.136526 -3.09036 -0.312215 0.0685499 -0.00623336 -0.0573417 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 793 794 5.39772 0.181356 -0.45949 0.0179753 0.109447 0.0378973 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 744 794 0.122074 -3.13615 -0.0690339 0.0716314 0.015146 0.018444 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 794 795 5.26147 0.0881441 -0.462425 0.000927567 0.123707 0.0463908 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 745 795 -0.0408824 -3.06165 -0.180283 0.0552084 0.00107738 0.03285 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 795 796 5.24086 0.0843215 -0.230388 0.01595 0.110735 0.0735558 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 746 796 0.0291763 -3.14629 -0.121005 0.0535681 0.0112398 -0.0476228 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 796 797 5.4018 0.0630877 -0.438817 -0.011858 0.128578 0.0284576 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 747 797 0.00995621 -3.09276 -0.134331 0.0710484 -0.0107197 -0.0420688 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 797 798 5.18226 0.00183321 -0.282823 -0.00976103 0.0920822 0.069275 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 748 798 -0.229286 -2.88429 -0.0733723 0.0628713 0.00159554 0.0224301 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 798 799 5.49213 0.318543 -0.236335 -0.00890456 0.0986672 0.0576018 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 749 799 0.0947196 -3.10909 -0.00814159 0.0741363 -0.00183075 -0.0274043 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 799 800 5.19784 0.0269897 -0.132272 -0.00320711 0.104496 0.114689 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 750 800 0.139404 -2.95773 -0.0703432 0.058182 -0.0051102 -0.026768 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 800 801 5.36766 0.118349 -0.227007 0.00833261 0.100888 0.0785892 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 751 801 -0.18957 -3.11952 0.0212357 0.0730987 0.00696412 -0.00842283 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 801 802 5.29734 0.0321226 -0.301724 -0.00357714 0.0962285 0.115381 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 752 802 -0.0838925 -3.13107 -0.192335 0.0634132 0.014516 0.0288194 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 802 803 5.08873 0.375587 -0.333561 0.0108267 0.1075 0.0262502 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 753 803 0.0237125 -2.91934 -0.282738 0.0639136 -0.00187631 0.0126091 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 803 804 5.26387 0.118944 -0.284624 -3.1821e-05 0.118843 0.0422896 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 754 804 0.0289448 -3.15941 -0.0906228 0.0448238 -0.00331117 -0.00142978 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 804 805 5.38505 -0.0123196 -0.252434 0.00948839 0.0858826 0.0770298 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 755 805 0.00110749 -3.21089 0.0477078 0.0534735 -0.00243264 0.0211487 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 805 806 5.50148 0.270317 -0.370595 0.00579029 0.099864 0.0422823 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 756 806 0.0533136 -2.97653 -0.0578557 0.06795 -0.0229109 -0.0355867 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 806 807 5.42807 0.0265666 -0.143237 -0.00168787 0.118841 0.133913 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 757 807 0.0501075 -3.12399 0.100344 0.0699577 -0.0202014 0.0192439 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 807 808 5.35942 0.0292008 -0.322296 -0.00311433 0.100764 -0.0422457 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 758 808 0.0597505 -2.93625 -0.0114413 0.0625734 -0.00702917 -0.0331654 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 808 809 5.48797 0.280071 -0.321361 0.013126 0.102316 0.0597303 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 759 809 -0.0970999 -3.08923 -0.195035 0.0473844 -0.00729651 0.0252052 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 809 810 5.19527 0.225186 -0.288108 -0.011669 0.113584 0.109592 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 760 810 0.192883 -3.12142 -0.0530891 0.077817 0.00637572 -0.00350111 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 810 811 5.42915 -0.103176 -0.377902 0.0248556 0.0877771 0.0359431 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 761 811 -0.0395695 -3.06851 -0.313869 0.067643 0.00703421 0.0181108 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 811 812 5.40434 0.0836267 -0.377622 -0.00354704 0.101012 0.0487211 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 762 812 0.0564086 -3.06752 0.0406841 0.0643097 -0.00896107 0.0215275 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 812 813 5.27955 0.10831 -0.0775811 0.00186326 0.086852 0.0301668 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 763 813 -0.0523111 -3.21446 0.161864 0.0446022 0.0110227 -0.0163725 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 813 814 5.31338 0.157936 -0.192599 -0.00520697 0.100725 0.150978 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 764 814 0.0710168 -3.02492 -0.010862 0.0848809 -0.00436382 0.00852261 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 814 815 5.43932 0.049648 -0.189942 0.00864415 0.110105 0.0170614 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 765 815 0.0274515 -2.82089 -0.197057 0.061044 0.000424802 -0.0540304 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 815 816 5.37214 0.170266 -0.11408 0.00580319 0.102471 0.0639901 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 766 816 -0.0747144 -3.01466 -0.0141552 0.0676841 -0.0119294 0.00194098 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 816 817 5.43239 0.244191 -0.336115 -0.00503401 0.107893 -0.0233215 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 767 817 -0.167955 -2.95638 -0.0868385 0.0566331 0.00628874 -0.0146945 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 817 818 5.41394 0.182768 -0.465227 -0.0063678 0.107568 0.0626569 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 768 818 0.216837 -2.77782 -0.00104291 0.0453445 0.00575401 0.0952461 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 818 819 5.4727 0.182763 -0.361857 0.00336686 0.121225 0.118431 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 769 819 -0.0817631 -3.05623 -0.0165462 0.0656581 0.0150448 0.105707 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 819 820 5.33132 0.0880952 -0.132311 0.00307682 0.122254 0.0856968 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 770 820 -0.0594606 -3.01292 -0.0726309 0.0678638 0.00609485 0.00452306 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 820 821 5.41932 0.0351362 -0.347685 -0.000127612 0.117281 -0.000893112 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 771 821 0.0547593 -3.00883 -0.00264238 0.0633193 0.00704458 0.00263415 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 821 822 5.38314 0.229323 -0.217536 0.00112345 0.107214 0.0720548 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 772 822 0.169894 -3.15755 -0.271426 0.0642536 0.007527 0.0147595 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 822 823 5.44748 0.218967 -0.308589 0.00187153 0.110575 0.013727 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 773 823 -0.0341699 -2.95514 0.0818555 0.0592414 -0.00517063 -0.0542876 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 823 824 5.43172 0.209787 -0.450308 0.013103 0.0932253 0.029456 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 774 824 0.120443 -3.11704 -0.0224861 0.0584597 0.0178717 0.0463588 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 824 825 5.373 0.133324 -0.271507 -0.00131408 0.107804 0.0528033 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 775 825 -0.000459441 -3.19053 0.0264692 0.0755326 -0.00362131 0.00871091 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 825 826 5.46788 0.0849329 -0.229361 0.0116053 0.0963948 0.0682973 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 776 826 0.039589 -3.11227 -0.1894 0.0530115 0.0153331 0.00852723 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 826 827 5.38079 -0.127509 -0.102887 0.0250106 0.0998114 0.0912061 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 777 827 0.108719 -3.0155 -0.154969 0.0669255 -0.0154642 0.0874035 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 827 828 5.37724 -0.0326756 -0.138603 0.00581951 0.104075 0.00791883 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 778 828 0.08269 -3.0464 -0.0044232 0.0581182 -0.0229147 0.0312964 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 828 829 5.3739 0.035482 -0.321164 -0.00486669 0.0966779 0.0684455 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 779 829 0.0893296 -3.03656 -0.104166 0.0679718 0.0231424 0.0225762 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 829 830 5.33084 0.273933 -0.334283 -0.0126767 0.0987737 -0.0256534 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 780 830 -0.128343 -2.88215 -0.0714147 0.0587598 -0.00284567 0.0029651 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 830 831 5.52419 0.00794975 -0.227209 0.00578264 0.104423 0.0154299 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 781 831 -0.0714586 -3.04641 -0.0191768 0.0487401 -0.0110235 -0.0178563 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 831 832 5.42515 0.0714178 -0.478357 -0.000903342 0.0972547 0.0927954 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 782 832 0.0764801 -3.00032 0.120822 0.0520786 0.00494684 0.0826291 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 832 833 5.58756 0.210566 -0.307069 0.0162071 0.104831 -0.0143357 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 783 833 0.0855575 -2.98796 -0.213588 0.0768222 -0.00151586 -0.0297891 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 833 834 5.50835 0.184763 -0.228267 0.0137564 0.105822 0.0756419 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 784 834 0.221665 -3.04702 -0.297344 0.061733 -0.00932508 -0.0376221 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 834 835 5.61127 0.0507605 -0.17027 0.0114251 0.0952634 0.0284885 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 785 835 0.0742049 -2.93847 -0.161161 0.0634248 -0.00210513 0.0108337 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 835 836 5.48043 0.0209374 -0.418011 -0.00283636 0.12559 -0.017185 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 786 836 -0.151716 -3.13695 -0.203101 0.0668202 -0.00340238 -0.0012111 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 836 837 5.56699 0.175323 -0.351172 0.00180907 0.110506 0.0553422 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 787 837 -0.0894004 -2.88441 -0.136029 0.0825449 0.00152065 0.0354937 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 837 838 5.32762 0.11804 -0.350563 -0.000753829 0.0907529 0.0400098 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 788 838 0.0210524 -3.00989 -0.154816 0.0578179 -0.0146046 0.014603 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 838 839 5.42237 0.164304 -0.384447 0.0153668 0.0916537 0.0993906 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 789 839 -0.0140701 -3.2293 0.139781 0.0468194 -0.0128685 -0.0781856 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 839 840 5.44521 0.162823 -0.328552 0.0104145 0.0968614 0.148829 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 790 840 -0.0565142 -3.02495 -0.025964 0.0739753 0.018297 -0.00467218 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 840 841 5.61253 0.069914 -0.223577 0.0174301 0.119212 0.0460968 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 791 841 0.0164769 -3.13911 -0.106503 0.0637163 0.00857961 0.00943962 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 841 842 5.39787 0.258225 -0.197657 0.00438106 0.102756 0.0815166 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 792 842 0.0203868 -3.29879 -0.159645 0.0640894 0.0012212 -0.0503669 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 842 843 5.43317 -0.085881 -0.210751 0.00805972 0.107217 0.0983152 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 793 843 0.0103455 -2.78627 -0.0255142 0.0776721 0.00849335 0.0329023 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 843 844 5.40771 0.215645 -0.200565 0.0256466 0.105592 0.0599317 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 794 844 -0.0729561 -3.07995 -0.105971 0.0568126 0.00324068 -0.00766464 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 844 845 5.52266 0.0229137 -0.387959 0.0100185 0.117434 0.0598418 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 795 845 0.0618721 -3.06492 0.0399359 0.0707327 0.00123784 -0.0196934 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 845 846 5.49201 0.0676575 -0.366536 0.0106634 0.10972 -0.0236267 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 796 846 -0.0485375 -2.99825 -0.180241 0.061976 -0.00625801 0.080142 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 846 847 5.38153 0.0831649 -0.258973 0.000377965 0.098076 0.0835005 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 797 847 -0.124664 -3.00604 -0.0641998 0.0469996 -0.0108647 0.12554 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 847 848 5.35694 -0.0482841 -0.330069 0.0182184 0.129096 0.109391 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 798 848 0.0205685 -2.96612 0.0694419 0.077109 0.00444003 0.0286734 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 848 849 5.27639 0.0945423 -0.288511 -0.00284569 0.10812 0.0889412 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 799 849 0.0676333 -3.01993 -0.238978 0.0600366 -0.00477505 -0.0126593 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 849 850 5.44542 0.183225 -0.34732 0.0352274 0.111688 0.0404952 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 800 850 0.0754936 -3.06356 -0.116271 0.0650193 0.0101746 -0.0505819 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 850 851 5.55677 0.286422 -0.438426 -0.00545376 0.109529 0.0217729 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 801 851 0.052372 -3.12787 -0.0102487 0.0643244 -0.00419776 0.0126394 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 851 852 5.52507 0.118717 -0.196016 0.0195774 0.105559 0.0351438 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 802 852 0.0471629 -3.07179 0.25904 0.0680487 0.0128719 -0.0125969 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 852 853 5.46886 0.159076 -0.271589 0.0114994 0.0966973 0.108508 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 803 853 -0.0385874 -3.096 -0.1376 0.0671632 0.0108091 0.0187646 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 853 854 5.51199 0.217291 -0.299369 0.00440555 0.132907 0.0390139 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 804 854 -0.0372246 -3.02773 -0.294749 0.0655991 -0.0114882 -0.0156043 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 854 855 5.51543 0.283903 -0.381323 0.0176572 0.106779 0.0590828 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 805 855 0.152984 -3.14281 0.0157709 0.0658771 -0.00263678 -0.054367 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 855 856 5.65074 -0.0270548 -0.216601 0.00163097 0.11022 -0.0073571 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 806 856 -0.0951268 -3.23544 -0.042613 0.0501963 -0.00169054 -0.0407583 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 856 857 5.30723 0.182254 -0.322114 0.00589103 0.111282 0.0572112 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 807 857 0.0551192 -3.09255 -0.114165 0.0427529 0.007684 0.0401774 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 857 858 5.5815 0.102338 -0.487154 -0.0037479 0.0981932 0.0550238 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 808 858 0.00516526 -3.17746 -0.10912 0.0664482 0.0100229 0.0208556 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 858 859 5.54776 -0.0447337 -0.342395 0.00463873 0.119114 0.00615207 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 809 859 -0.0471174 -3.05994 -0.0632384 0.0467488 -0.00668901 0.0537764 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 859 860 5.73325 -0.0703218 -0.298173 0.00186512 0.106859 0.0394859 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 810 860 0.0273089 -3.13088 -0.0920744 0.0469507 0.0208641 0.0066657 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 860 861 5.44636 -0.101466 -0.227333 0.0132672 0.104276 -0.0154156 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 811 861 0.251966 -3.12255 -0.0955193 0.0675776 0.00409941 -0.0486017 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 861 862 5.46832 0.0034815 -0.48038 0.0168354 0.107328 0.0637843 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 812 862 0.0608597 -3.08813 -0.138249 0.0679572 0.00889264 0.0604949 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 862 863 5.60754 0.110966 -0.340274 -0.000507501 0.115182 0.111914 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 813 863 -0.109336 -3.20256 -0.0661604 0.0622308 -0.0156592 0.0353477 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 863 864 5.6811 0.0430915 -0.330111 0.00423997 0.12454 0.0690777 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 814 864 0.0767307 -2.82207 0.0408218 0.0676136 0.00724741 0.0423628 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 864 865 5.53086 0.188418 -0.350275 0.00284788 0.0918312 0.0032867 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 815 865 0.174826 -3.06884 -0.244626 0.0603843 -0.0025261 0.041339 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 865 866 5.48949 0.142582 -0.318214 -0.0035865 0.0951289 0.0773789 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 816 866 -0.00499317 -2.98111 -0.153201 0.0440066 0.00265665 -0.0238713 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 866 867 5.82972 0.149178 -0.298758 0.00315607 0.122793 0.0050502 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 817 867 0.00560511 -3.01963 -0.252672 0.0649075 -0.0114234 0.0216059 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 867 868 5.57386 0.223666 -0.276354 -0.00104587 0.120213 0.0525573 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 818 868 -0.297951 -3.0727 0.0959597 0.0644723 0.00432807 -0.0328016 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 868 869 5.61316 0.0253105 -0.377634 -0.00695867 0.118322 -0.0114218 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 819 869 -0.0823634 -3.12234 -0.127509 0.0542311 0.00133779 -0.0403975 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 869 870 5.62345 -0.120347 -0.192941 -0.000277778 0.126276 0.0647631 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 820 870 -0.0146496 -2.90021 -0.12713 0.06483 0.0122235 0.0230018 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 870 871 5.69018 0.0424455 -0.410373 -0.00407878 0.127353 0.111729 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 821 871 -0.102696 -3.03492 0.0019022 0.06137 -0.0164409 0.0158564 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 871 872 5.62336 0.108373 -0.20576 0.00624347 0.122285 0.0482832 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 822 872 -0.0623595 -3.14125 -0.152182 0.0665468 -0.00494298 -0.0687816 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 872 873 5.63896 0.00598252 -0.294655 -0.00703519 0.0944308 0.0563393 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 823 873 0.206902 -2.83793 -0.265399 0.0539451 -0.0106572 -0.0081036 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 873 874 5.44794 0.176577 -0.379727 -0.00919274 0.126872 0.0403889 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 824 874 0.00242097 -2.98718 0.0651186 0.071002 0.00756906 0.00124292 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 874 875 5.47986 0.15967 -0.190827 -0.0012769 0.0901644 0.015987 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 825 875 -0.140471 -3.19624 -0.290119 0.0656985 0.000932556 -0.0642646 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 875 876 5.61406 -0.0213291 -0.266134 0.00429432 0.112224 0.0162696 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 826 876 0.0134897 -2.98252 -0.123038 0.0558555 -0.0177147 -0.142812 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 876 877 5.79605 0.114555 -0.34615 0.0215349 0.101346 0.0748463 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 827 877 -0.0057657 -2.98519 -0.0225819 0.0648041 0.0202072 0.0209343 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 877 878 5.55674 0.0988603 -0.207797 -0.00634477 0.105889 0.0847202 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 828 878 -0.00118392 -3.043 -0.0397329 0.0667516 -0.010456 -0.0436006 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 878 879 5.46382 0.141946 -0.254806 -0.00583483 0.117211 -0.0309035 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 829 879 -0.0541385 -3.04666 -0.135317 0.0488924 0.00974442 -0.00902855 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 879 880 5.68799 0.127466 -0.327294 -0.00899907 0.109082 0.139587 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 830 880 -0.0395402 -3.13943 -0.0582472 0.0488669 0.0112481 0.0491593 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 880 881 5.78704 0.106964 -0.528972 -0.0015892 0.118725 0.0665529 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 831 881 -0.162072 -3.05012 -0.105102 0.065211 -0.00035457 0.00359769 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 881 882 5.72918 0.138789 -0.156362 -0.00154343 0.100118 0.0953245 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 832 882 -0.0389838 -3.2889 -0.060577 0.0786346 -0.00232569 0.0595627 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 882 883 5.86222 0.0796744 -0.241965 0.00487163 0.129456 0.0928662 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 833 883 -0.02885 -3.05762 -0.0613176 0.0568149 0.00792373 -0.0182448 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 883 884 5.74574 0.117091 -0.0058916 0.00856249 0.105505 0.055369 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 834 884 -0.0767035 -2.91371 -0.0139103 0.0537297 0.00636968 0.00771971 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 884 885 5.51883 -0.00973307 -0.438069 0.00183971 0.114528 0.0788894 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 835 885 0.145044 -3.18457 -0.0862953 0.0645326 0.00124387 0.0610584 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 885 886 5.60348 0.213426 -0.329835 0.00921274 0.119903 0.0782399 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 836 886 0.0105162 -2.94827 -0.0144536 0.0633864 0.00474876 -0.0265795 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 886 887 5.74311 0.13457 -0.423206 0.00967385 0.0948428 0.104191 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 837 887 -0.0145459 -2.98616 -0.070004 0.054668 0.000173385 -0.040764 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 887 888 5.65981 0.14786 -0.205742 0.0050061 0.107568 0.0499248 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 838 888 0.120328 -3.01565 -0.175568 0.0577028 0.00752391 0.0458964 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 888 889 5.62041 0.125545 -0.399808 0.00236579 0.113118 0.118538 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 839 889 -0.00527073 -2.89964 -0.166186 0.071987 -0.0194947 0.0322962 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 889 890 5.79303 0.153249 -0.341452 0.00979922 0.117016 0.0855099 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 840 890 -0.0661851 -3.09684 -0.143534 0.0534907 0.00666852 0.0469769 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 890 891 5.85574 -0.0637915 -0.421095 -0.00198457 0.12123 0.0597487 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 841 891 0.0175324 -3.23279 -0.175266 0.0468126 -0.00283092 -0.0302702 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 891 892 5.73138 -0.0787459 -0.407888 0.016708 0.121855 0.0582726 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 842 892 -0.0641623 -3.1783 0.0883321 0.0578649 -0.00330838 0.0691626 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 892 893 5.60928 0.0926899 -0.382789 0.00821818 0.107891 -0.0299389 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 843 893 -0.0394914 -3.00401 -0.104158 0.0621685 0.00151955 -0.00214253 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 893 894 5.67846 0.160198 -0.326742 0.0062275 0.111128 0.100415 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 844 894 0.0570183 -3.00372 -0.274852 0.0738882 0.00832292 0.0188151 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 894 895 5.68276 0.0336129 -0.272 0.00057233 0.126866 0.0709469 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 845 895 -0.0380615 -3.10552 -0.140992 0.0638313 -0.0019301 -0.0175082 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 895 896 5.67846 -0.0196392 -0.483228 -0.00375038 0.110561 0.0353133 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 846 896 -0.0796676 -2.87112 -0.0243779 0.0644395 0.00141475 -0.000537595 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 896 897 5.70897 -0.0344093 -0.313103 -0.000494778 0.116177 0.00908831 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 847 897 -0.0672669 -2.86321 0.117066 0.0541894 -0.0100323 -0.000995567 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 897 898 5.8709 0.0972814 -0.176418 0.0063692 0.119902 0.0187295 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 848 898 0.106736 -3.17697 -0.00982482 0.0631819 -0.00555778 0.00902965 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 898 899 5.68489 0.113443 -0.288222 -0.00895948 0.108205 0.108482 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 849 899 -0.123366 -3.07337 -0.0261452 0.060131 -0.00948015 0.0286471 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 899 900 5.71728 0.00504936 -0.166699 0.0151203 0.100867 0.103704 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 850 900 0.0514619 -3.01406 -0.00618753 0.0787327 -0.00129161 0.00294897 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 900 901 5.81606 0.130423 -0.307906 0.00177775 0.103953 0.0582778 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 851 901 0.129484 -2.98772 -0.107677 0.0890209 0.0108462 0.0257882 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 901 902 5.58134 0.106567 -0.366241 0.00636359 0.106493 0.0598277 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 852 902 0.186296 -3.01508 -0.0508652 0.0538734 -0.0029991 -0.0306229 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 902 903 5.66485 0.0396712 -0.491777 0.00543491 0.11764 0.0719504 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 853 903 -0.0617121 -2.92871 -0.187727 0.0627519 -0.0152531 -0.00339369 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 903 904 5.78158 -0.0729035 -0.267288 -0.00268518 0.10262 0.117285 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 854 904 0.0657111 -2.91251 -0.153895 0.0591152 -0.00812452 0.0379513 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 904 905 5.71539 0.110967 -0.316183 0.00890228 0.115505 0.0816919 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 855 905 0.0576527 -2.9949 -0.0201603 0.0643084 -0.00387708 -0.0246904 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 905 906 5.61754 0.00202861 -0.257216 0.0112767 0.11772 0.0186353 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 856 906 -0.072813 -3.03136 -0.135348 0.0785048 0.00291089 -0.0408013 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 906 907 5.66768 0.00672407 -0.43321 0.013643 0.100485 -0.0305147 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 857 907 -0.0950345 -3.13145 -0.114097 0.0616122 0.00699456 -0.0397035 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 907 908 5.74752 0.088552 -0.375093 -0.0172569 0.114828 0.0836396 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 858 908 -0.0824084 -2.95155 -0.0565634 0.0550739 0.013475 -0.0837597 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 908 909 5.74854 0.0195906 -0.432354 -0.00133347 0.120554 0.0344148 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 859 909 0.135732 -3.14951 -0.13595 0.0627147 0.017062 0.00260443 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 909 910 5.75807 0.0225051 -0.510702 0.000449932 0.10978 0.102883 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 860 910 0.0645128 -3.09717 -0.0901706 0.0686501 0.0153251 0.0164404 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 910 911 5.89262 0.168562 -0.386208 -0.0122869 0.119459 -0.01978 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 861 911 0.133169 -3.11375 -0.179508 0.0563896 0.00554515 0.00646966 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 911 912 5.8348 0.140481 -0.282375 0.0151944 0.109572 0.0633228 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 862 912 0.208141 -3.06997 -0.275004 0.0695253 -0.00527307 0.0261105 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 912 913 5.59309 0.202325 -0.398574 0.0189627 0.114065 -0.0394421 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 863 913 0.0228452 -3.08999 -0.161828 0.0759145 0.00132259 0.00384099 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 913 914 5.63077 0.0391913 -0.313469 0.00620642 0.125196 0.0362862 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 864 914 -0.173054 -3.13543 -0.116261 0.0532399 0.0138001 -0.0201843 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 914 915 5.73142 0.0274934 -0.268815 -0.00389896 0.0965665 0.0516985 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 865 915 -0.0217807 -2.9891 -0.128035 0.0761984 -0.0141238 -0.0604898 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 915 916 5.71058 0.154148 -0.443108 0.00311788 0.128862 0.0674009 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 866 916 -0.1345 -3.07454 -0.15849 0.06658 0.0154465 -0.0605996 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 916 917 5.87182 0.186107 -0.260194 0.00222168 0.10634 0.0170501 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 867 917 0.022569 -3.07268 -0.0394752 0.0494245 -0.00369295 0.00146992 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 917 918 5.83543 0.123671 -0.422451 -0.000657822 0.120018 0.140724 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 868 918 0.113911 -2.98425 -0.047503 0.0484126 -0.0106649 0.00920957 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 918 919 5.63953 0.0833965 -0.361634 0.0130403 0.106961 0.057925 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 869 919 0.0935929 -2.8295 -0.189479 0.0579376 0.015114 -0.0721362 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 919 920 5.74183 0.046585 -0.415589 -0.00724635 0.108646 -0.0168076 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 870 920 -0.143523 -2.85812 -0.120242 0.0681002 0.00275955 -0.0458604 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 920 921 5.83403 0.0342787 -0.272573 -0.0090147 0.128102 -0.0311093 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 871 921 -0.164815 -3.13075 -0.130331 0.0553706 -0.0119622 0.010073 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 921 922 5.66737 0.0669562 -0.452664 0.00267173 0.101129 0.0607469 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 872 922 0.152668 -3.13297 0.0524221 0.0612179 -0.00604264 0.0342896 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 922 923 5.70358 0.0310954 -0.289324 -0.0162986 0.0950071 0.102293 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 873 923 0.110593 -3.24041 -0.187065 0.0599794 0.00924838 -0.021805 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 923 924 5.61169 0.139257 -0.367081 0.0270063 0.112215 -0.00191026 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 874 924 -0.179357 -2.99108 -0.120697 0.064618 -0.012754 -0.00829556 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 924 925 5.69891 0.0508799 -0.393864 0.00318184 0.0999299 0.0847622 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 875 925 0.0464449 -3.18683 -0.168479 0.0657639 0.00953888 0.0612318 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 925 926 5.88813 0.228558 -0.19915 -0.0109772 0.143133 0.0343204 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 876 926 -0.00381915 -3.10149 -0.0986604 0.0684909 -0.00776917 0.0667639 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 926 927 5.88074 0.142328 -0.447172 -0.0091385 0.111694 0.0711913 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 877 927 0.041688 -3.21411 -0.132363 0.0743085 -0.00270315 0.0471978 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 927 928 5.76557 0.178848 -0.369578 0.00221802 0.106501 0.0117871 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 878 928 -0.00643717 -2.87597 -0.0149175 0.0722528 0.0108956 0.010617 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 928 929 5.70815 0.0326216 -0.244624 0.00666373 0.124035 0.0302921 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 879 929 0.0588748 -3.09383 -0.188432 0.0545491 0.000348733 -0.060142 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 929 930 5.83768 0.00219686 -0.328391 0.0150373 0.111617 0.0942473 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 880 930 -0.0138014 -3.06391 -0.170621 0.0735855 0.00507305 0.0333795 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 930 931 5.90511 -0.0241702 -0.27371 -0.0113712 0.125803 0.00628711 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 881 931 0.108728 -3.12562 0.0733991 0.0529694 -0.00238387 -0.0441871 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 931 932 5.84093 0.0277419 -0.364922 0.0198569 0.127319 0.0320153 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 882 932 0.0719464 -3.01479 -0.220671 0.0433315 0.0111216 0.0159775 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 932 933 5.80103 0.342445 -0.311277 -0.011791 0.114894 0.0664954 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 883 933 0.0731653 -3.12337 0.036976 0.0546755 -0.000236786 0.0605988 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 933 934 5.84555 0.127618 -0.289495 0.00635182 0.121654 0.00986428 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 884 934 -0.0267161 -3.05159 -0.0843282 0.0508906 0.00154887 -0.0673117 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 934 935 5.7416 0.256171 -0.276999 0.033529 0.132517 0.0292434 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 885 935 0.23322 -3.1108 0.0916384 0.0646734 0.00554178 0.0366757 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 935 936 5.73812 0.324558 -0.304425 -0.00885694 0.102511 0.0734478 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 886 936 -0.156601 -2.97509 -0.0986761 0.0645083 -0.014308 0.00539802 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 936 937 5.90347 0.154624 -0.182696 0.00953335 0.135071 0.0993044 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 887 937 -0.0366022 -3.10577 -0.153094 0.0710203 0.0223415 0.013002 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 937 938 5.78436 0.244822 -0.315574 -0.00517519 0.115547 0.0794457 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 888 938 -0.10024 -2.92706 -0.289488 0.0614908 -0.00223339 0.00484492 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 938 939 5.91267 -0.00339733 -0.36096 0.0216386 0.146158 0.078458 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 889 939 0.0663865 -3.01716 0.0277817 0.0743617 0.00858848 -0.0434251 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 939 940 5.6436 0.0739063 -0.545369 -0.000694263 0.0987482 0.0103039 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 890 940 0.0893573 -3.07206 0.0981277 0.0664399 0.00432704 -0.00081773 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 940 941 6.14703 0.0470746 -0.412763 0.00594781 0.108138 0.0520303 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 891 941 0.0978213 -3.04167 -0.0766208 0.0427588 0.010634 -0.0483327 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 941 942 5.93524 0.180158 -0.368718 0.00111394 0.133292 0.0162197 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 892 942 -0.00161554 -3.09857 -0.00185938 0.0731623 0.00376455 -0.0160248 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 942 943 5.6897 -0.0722077 -0.43154 0.000801379 0.124512 0.110326 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 893 943 0.0209751 -3.16323 -0.134262 0.0670576 0.00997867 0.0775382 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 943 944 5.9741 -0.0735058 -0.255266 0.00825349 0.128401 0.0473012 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 894 944 0.182204 -3.07618 -0.139507 0.0492743 -0.00841748 -0.00133312 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 944 945 5.94247 0.207794 -0.351528 0.00104922 0.123517 0.0750056 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 895 945 -0.0416307 -3.08688 -0.245167 0.0674619 -0.0221368 0.0245415 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 945 946 5.81961 0.0534436 -0.343714 0.0079812 0.13621 0.0265039 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 896 946 0.147749 -3.25451 -0.220992 0.0555959 0.00139987 -0.0668342 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 946 947 5.76548 -0.00733043 -0.535869 0.01101 0.107925 0.100967 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 897 947 0.0477481 -2.97821 -0.220782 0.0635092 0.00120738 0.01634 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 947 948 5.93372 0.160423 -0.245852 -0.0105612 0.110863 0.071377 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 898 948 0.0862325 -3.07872 -0.242241 0.0474091 -0.00161979 -0.0913925 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 948 949 5.83659 0.190445 -0.278819 -0.00573364 0.116972 0.0692949 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 899 949 -0.0340798 -3.01524 -0.31136 0.0510148 -0.00793078 -0.0531107 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 949 950 5.80575 0.0490006 -0.217435 0.00965528 0.129397 0.0716405 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 900 950 0.0314062 -3.20278 0.0229703 0.0408542 -0.00531462 -0.0297082 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 950 951 5.94037 -0.105746 -0.383996 0.00480533 0.123295 0.0209278 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 901 951 0.130807 -3.07881 -0.156298 0.0609175 0.00627261 0.0524152 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 951 952 5.93269 0.118407 -0.361279 0.00448006 0.112453 0.0864886 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 902 952 0.123132 -3.00814 -0.11484 0.0645225 -0.00726641 -0.00984185 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 952 953 5.77817 0.122147 -0.168345 -0.00855567 0.115176 0.0996461 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 903 953 -0.018327 -2.932 -0.00186501 0.0569702 0.00410564 0.0123333 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 953 954 5.87231 0.0449308 -0.325559 0.0087398 0.115921 0.0883216 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 904 954 -0.049517 -2.96606 -0.111201 0.0759981 0.01359 0.0195804 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 954 955 5.95759 -0.10446 -0.461411 -0.00317467 0.100563 0.00989361 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 905 955 0.229266 -3.11498 -0.223046 0.0635466 0.00990741 -0.0438346 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 955 956 5.78406 0.0738019 -0.441606 0.00483629 0.132172 -0.00585784 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 906 956 0.0738805 -2.97624 0.0149636 0.0789268 -0.0102231 -0.0497579 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 956 957 5.95271 0.145364 -0.482912 -0.00172477 0.103041 0.11615 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 907 957 0.0781099 -2.94845 0.041319 0.062285 0.00523114 -0.0263351 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 957 958 5.98294 0.0981044 -0.314154 -0.00698192 0.117709 0.0458176 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 908 958 0.169471 -3.10141 -0.0932237 0.0795286 -0.0180737 0.00635261 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 958 959 5.7759 0.128567 -0.228232 0.0127759 0.133689 0.0156009 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 909 959 -0.149071 -3.00445 -0.0775245 0.0568293 -0.0143429 0.0188036 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 959 960 5.89375 0.0637932 -0.254576 0.00618815 0.109029 0.00967233 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 910 960 -0.132917 -2.78686 -0.105742 0.0550426 0.00603796 -0.00611394 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 960 961 5.9505 -0.0616201 -0.446693 -0.0208308 0.118784 0.0281147 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 911 961 0.0432995 -3.121 0.00564701 0.0730457 -0.000563106 0.0062399 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 961 962 5.8297 0.085111 -0.342315 -0.00202488 0.138658 -0.0256182 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 912 962 0.0811981 -3.1013 -0.105646 0.0823669 0.00364722 -0.015005 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 962 963 5.8165 0.221306 -0.185925 -0.00589091 0.112857 0.00861302 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 913 963 -0.232083 -3.11313 -0.10773 0.0569758 0.00304915 -0.0038394 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 963 964 6.00393 -0.00931952 -0.462183 -0.00454362 0.127775 0.0578766 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 914 964 0.030681 -2.99322 -0.0111456 0.0528007 0.00763373 -0.0309236 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 964 965 5.86789 0.0261723 -0.306497 0.00241238 0.111484 0.0428847 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 915 965 0.0777047 -3.13883 -0.0212222 0.0579308 0.000774597 -0.00978926 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 965 966 5.98908 0.0378531 -0.256978 -0.00739232 0.128456 0.0762562 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 916 966 0.0671234 -3.21668 -0.0925357 0.0591847 0.00220768 0.0410104 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 966 967 5.93551 0.266178 -0.358432 0.000255048 0.103896 0.0526172 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 917 967 0.055155 -3.1811 -0.0594103 0.0571803 -0.00402892 0.0858504 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 967 968 5.78028 0.228768 -0.360943 0.00156527 0.118668 0.102718 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 918 968 -0.0307255 -3.15193 0.0216286 0.0581273 -0.000945855 -0.044067 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 968 969 5.7936 0.0885477 -0.277645 -0.0117364 0.112363 0.0483899 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 919 969 0.0815884 -3.23011 -0.0179284 0.0465296 0.000997434 -0.0309407 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 969 970 5.91996 0.0673377 -0.349883 0.00862644 0.118104 0.14286 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 920 970 0.0373945 -3.02067 -0.0581669 0.0546434 0.012708 0.0316409 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 970 971 5.89389 0.168067 -0.444025 0.00420566 0.104966 0.0211506 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 921 971 0.0661091 -3.17381 -0.16367 0.0664496 0.00435437 -0.0196274 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 971 972 5.84825 0.149212 -0.287992 0.0146029 0.103478 0.0682334 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 922 972 -0.160708 -3.05045 -0.243504 0.0624209 0.02044 0.015893 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 972 973 6.02934 0.0713096 -0.27386 0.0256645 0.134482 0.0539952 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 923 973 -0.117801 -3.11897 -0.245365 0.0601549 -0.0063569 0.0361674 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 973 974 5.91278 0.131277 -0.509767 0.00773773 0.117834 0.0465795 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 924 974 -0.0462526 -2.9713 -0.15525 0.0593279 0.0100355 -0.0303601 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 974 975 5.832 0.0566081 -0.246129 0.00370733 0.119746 -0.0253347 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 925 975 0.0561672 -2.96208 -0.297658 0.0560562 -0.00872338 0.021644 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 975 976 5.78135 0.0543821 -0.423562 -0.00489479 0.1251 -0.0708398 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 926 976 0.226172 -2.94283 -0.184377 0.0870218 0.012055 -0.0115809 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 976 977 5.87459 0.140453 -0.474698 6.55509e-05 0.127088 0.021701 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 927 977 -0.045037 -3.02154 -0.106196 0.0515899 0.00274159 0.0366376 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 977 978 5.90999 0.0765201 -0.34204 -0.00117448 0.108235 0.084709 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 928 978 -0.0921606 -3.01449 -0.144193 0.0577033 -0.0125742 0.00148354 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 978 979 5.91373 -0.0464542 -0.424729 -0.00175246 0.119142 0.0554509 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 929 979 -0.0591735 -3.19667 -0.0879218 0.055739 0.00278888 -0.00604483 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 979 980 5.92006 -0.0370302 -0.394517 0.00175098 0.126061 0.0010585 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 930 980 -0.00201238 -3.11049 0.0113263 0.0523772 0.00542789 -0.0204863 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 980 981 5.67788 0.160756 -0.482692 -0.0138013 0.130793 0.0195738 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 931 981 -0.24441 -3.02352 -0.181153 0.0573253 -0.000853116 0.0146156 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 981 982 5.81624 -0.0320606 -0.355133 0.0116294 0.107808 -0.00469732 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 932 982 0.033071 -3.04145 0.0382333 0.0657392 0.000871986 -0.0433737 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 982 983 6.01713 0.210474 -0.204899 0.021088 0.130198 0.0405009 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 933 983 0.0436633 -3.1605 -0.195206 0.0620472 -0.00666152 0.076645 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 983 984 5.92896 0.0675336 -0.57383 -0.00585476 0.126578 0.0838544 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 934 984 -0.0459296 -2.85428 -0.186596 0.0671636 -0.00187333 0.00301786 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 984 985 6.11662 0.020977 -0.424975 0.00816502 0.113181 0.0442294 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 935 985 0.0203099 -2.95208 -0.0260574 0.0685339 0.00147742 0.0482901 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 985 986 5.87066 0.0469223 -0.506174 -0.00298515 0.0952878 0.0224686 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 936 986 -0.182141 -3.10238 -0.238111 0.0698601 0.00222993 0.020132 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 986 987 5.91167 0.103836 -0.465919 0.000893594 0.124621 0.00877801 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 937 987 0.0267933 -3.04949 -0.129168 0.0586268 -0.0121383 0.00168218 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 987 988 5.8007 0.0691662 -0.407599 -0.021429 0.133207 0.016605 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 938 988 -0.0819009 -3.0526 -0.118019 0.0705099 0.0178594 -0.0780517 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 988 989 5.92943 0.0156208 -0.199829 -0.0142409 0.115684 0.0578818 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 939 989 -0.0570242 -2.99449 0.0191212 0.0686818 0.0095252 -0.0213175 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 989 990 5.98538 0.110079 -0.419333 0.022156 0.114461 0.065051 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 940 990 0.0616481 -3.06456 0.0486347 0.0684938 -0.00890722 0.00528942 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 990 991 5.99323 0.060736 -0.552609 -0.00211683 0.115178 0.100135 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 941 991 -0.0672321 -2.93812 -0.0297879 0.0708174 0.0148777 0.00790822 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 991 992 5.87864 0.00983747 -0.301448 0.00664587 0.133948 0.0416467 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 942 992 -0.0582761 -3.13893 -0.247103 0.0667328 -0.00121704 0.00750106 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 992 993 6.05482 0.0756201 -0.41822 0.00283092 0.128495 0.117523 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 943 993 -0.0755444 -2.81495 -0.187806 0.0543995 -0.004082 0.0464925 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 993 994 6.03533 0.0059417 -0.304103 0.0036887 0.102961 -0.00603561 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 944 994 0.153973 -3.269 -0.0465982 0.0671981 0.00690557 0.0563223 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 994 995 6.03443 0.12901 -0.252569 0.0140838 0.119445 0.115117 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 945 995 -0.05785 -3 -0.11265 0.0698289 -0.00615208 -0.000365173 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 995 996 5.96137 0.0238147 -0.302607 0.011709 0.109706 0.0763255 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 946 996 -0.101075 -3.34018 -0.00949362 0.0703672 -0.0144498 -0.0541034 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 996 997 5.95767 0.0792133 -0.469595 0.00582529 0.120029 0.0803362 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 947 997 0.116916 -3.00919 -0.132406 0.0530687 -0.0112767 0.0698936 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 997 998 5.78988 0.181554 -0.349835 -0.00400251 0.113389 0.0224244 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 948 998 -0.0515803 -2.84711 -0.0145609 0.0546773 0.00695092 0.0226123 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 998 999 5.99736 0.0144268 -0.270316 -0.00702106 0.127906 0.0335552 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 949 999 0.0227854 -3.11563 -0.0776197 0.0602293 -0.00144853 -0.00859518 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 999 1000 6.02616 0.16531 -0.61513 0.00798092 0.1269 0.019448 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 950 1000 -0.0304937 -3.03547 -0.11559 0.0700084 0.012317 0.0392633 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1000 1001 5.87236 0.0343077 -0.196024 0.00738804 0.134282 0.0767825 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 951 1001 0.0840092 -2.95577 -0.017715 0.0865725 0.00121891 -0.00545879 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1001 1002 6.00823 0.187838 -0.18849 0.00767158 0.128257 0.0272487 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 952 1002 0.083814 -3.03054 -0.0857193 0.0599518 -0.0022857 -0.00430316 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1002 1003 5.94887 0.0268525 -0.230844 -0.0108393 0.113799 0.0839244 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 953 1003 -0.0817822 -3.00663 -0.136828 0.0790884 0.00225068 0.0329214 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1003 1004 5.80156 0.0651958 -0.4677 0.00422433 0.125709 0.0111342 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 954 1004 -0.133527 -3.11044 -0.21021 0.0840047 -0.0285565 0.112517 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1004 1005 6.0407 0.140861 -0.372566 0.00857235 0.103025 -0.0161311 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 955 1005 0.163475 -3.11015 -0.0109611 0.0680815 -0.0173532 0.049124 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1005 1006 5.87842 -0.0265365 -0.626934 0.00608827 0.117344 0.107922 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 956 1006 0.088096 -3.15635 -0.127318 0.06994 0.0164995 -0.0398786 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1006 1007 5.83783 0.0109809 -0.340803 0.0090729 0.121909 0.0471533 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 957 1007 -0.0151472 -2.95095 -0.151123 0.0431925 -0.0145254 -0.0390335 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1007 1008 6.03981 0.051088 -0.538192 0.0167969 0.114486 0.0973489 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 958 1008 -0.0279193 -3.03789 -0.0273645 0.0622433 -0.00230048 0.00544718 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1008 1009 5.86934 0.0524011 -0.357282 0.0114007 0.112558 0.0428634 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 959 1009 -0.275265 -2.85042 -0.0567159 0.0554497 0.00700271 -0.00609385 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1009 1010 6.0856 -0.0641573 -0.228599 0.00160243 0.118649 -0.00469985 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 960 1010 0.0303055 -3.00106 -0.0687602 0.0719371 0.0132331 -0.0318831 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1010 1011 5.91605 0.0942708 -0.400208 0.0100291 0.119557 0.045976 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 961 1011 0.207652 -3.07523 -0.10412 0.0696832 -0.00801302 -0.0763837 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1011 1012 5.90871 0.0513194 -0.363139 0.00738567 0.12125 0.00826238 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 962 1012 -0.0622008 -3.17816 -0.349235 0.0524629 -0.00672636 0.00919596 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1012 1013 6.16339 -0.00735077 -0.317404 0.00734191 0.124362 0.00563829 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 963 1013 -0.106456 -3.08668 -0.0620185 0.0820027 -0.00111664 -0.00121897 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1013 1014 6.10255 0.0940275 -0.635988 0.00728009 0.0995202 0.0384983 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 964 1014 -0.164922 -3.05599 -0.0657857 0.0579574 0.00578415 0.020974 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1014 1015 6.27194 0.102547 -0.211161 0.0138729 0.110419 0.0648463 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 965 1015 -0.031883 -3.03663 -0.245354 0.0443117 -0.0216675 0.0744507 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1015 1016 6.10932 0.0610938 -0.221518 0.00581769 0.120043 0.0194876 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 966 1016 -0.141263 -3.00011 -0.0275538 0.0572684 0.00989163 0.0107657 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1016 1017 5.97724 0.0958543 -0.326323 -0.0181937 0.123108 0.0405011 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 967 1017 -0.0167885 -2.90299 -0.0969139 0.0644305 0.00176229 0.0447208 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1017 1018 6.18252 -0.0466147 -0.480401 0.00881654 0.135978 0.047472 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 968 1018 -0.0860026 -3.04599 -0.132652 0.0445599 0.00924848 -0.0494069 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1018 1019 5.86558 -0.0521078 -0.200907 -0.0142739 0.123925 0.0950651 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 969 1019 -0.0851597 -2.90807 -0.0658584 0.0467597 -0.00181803 0.0338525 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1019 1020 6.00306 -0.0442583 -0.379921 -0.00814603 0.128117 -0.0121779 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 970 1020 -0.0396013 -3.08293 0.0506673 0.0666653 -0.000767108 0.00219506 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1020 1021 5.94107 0.0144093 -0.24275 -0.00193209 0.119015 0.118382 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 971 1021 0.250576 -3.15329 -0.01005 0.0825083 0.0105149 -0.00420336 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1021 1022 6.08892 0.231953 -0.176065 -0.00878297 0.121511 -0.018491 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 972 1022 -0.117976 -3.1559 -0.198695 0.0493489 -0.00191379 0.0374746 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1022 1023 6.03162 0.180877 -0.421028 0.00122719 0.126431 -0.0206739 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 973 1023 0.0333009 -3.00712 -0.133243 0.056294 0.0134939 0.0253223 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1023 1024 6.00148 0.129429 -0.372576 -0.00324585 0.111877 0.0875596 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 974 1024 0.0674308 -3.17344 -0.247803 0.0675724 -0.000510293 0.0475125 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1024 1025 6.05035 0.174562 -0.415445 -0.0104056 0.108639 0.0588222 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 975 1025 0.0496622 -3.02014 -0.0797395 0.0579268 0.0174453 0.0278119 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1025 1026 5.99791 0.128957 -0.452235 0.000154361 0.111976 -0.00325675 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 976 1026 0.0947565 -3.11326 -0.0268186 0.0676865 0.0050996 -0.0264718 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1026 1027 6.13104 0.0557912 -0.494837 0.0269934 0.118852 0.0360486 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 977 1027 0.00946112 -2.96368 -0.199493 0.0585492 -0.000676508 -0.0368704 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1027 1028 6.19718 0.00188284 -0.0350639 -0.00955501 0.1273 -0.0384479 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 978 1028 -0.155117 -2.95919 -0.00336052 0.0535169 -0.00421628 -0.0149222 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1028 1029 6.04898 -0.149089 -0.43079 0.00581417 0.111957 0.070227 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 979 1029 0.0282176 -2.97821 -0.0547399 0.0734951 0.0116447 0.0268212 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1029 1030 6.07776 0.213207 -0.460237 -0.00308963 0.103757 0.0544478 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 980 1030 0.0162313 -2.96715 -0.219687 0.0462596 -0.00738348 0.0848479 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1030 1031 5.96802 -0.00522613 -0.457727 -0.00657492 0.116739 0.0263718 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 981 1031 -0.0333699 -3.10039 -0.0891244 0.0479216 -0.00166146 -0.0687814 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1031 1032 6.22543 -0.182285 -0.205716 0.0107511 0.136033 -0.0117332 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 982 1032 0.0971304 -3.18518 -0.0758457 0.0667924 0.0260403 -0.01148 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1032 1033 5.92141 -0.0835197 -0.488146 -0.0180658 0.111202 0.0591831 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 983 1033 -0.00646451 -3.02791 -0.0224793 0.0643403 0.000866321 -0.0497889 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1033 1034 5.95662 0.131831 -0.471892 0.00873253 0.117292 -0.00757291 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 984 1034 -0.0419264 -3.08604 -0.0624456 0.0489771 0.0026509 0.138746 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1034 1035 6.16636 -0.0920027 -0.24997 0.00251567 0.139279 0.0717414 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 985 1035 0.00219053 -3.01637 -0.369443 0.0531906 0.0167349 0.00782572 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1035 1036 6.14762 -0.0920677 -0.371614 0.00537592 0.119448 -0.0338471 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 986 1036 -0.0333529 -3.02544 -0.0404052 0.0611655 -0.00360411 -0.0166452 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1036 1037 5.83265 0.192045 -0.309486 0.0186863 0.119958 0.0482069 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 987 1037 -0.109172 -3.07893 -0.350339 0.0777384 0.00887061 -0.00527102 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1037 1038 6.23999 0.0602393 -0.31331 0.0175159 0.113136 0.092817 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 988 1038 0.067169 -3.02183 -0.227826 0.0491288 0.0044626 0.00317888 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1038 1039 6.05938 -0.0866351 -0.498915 0.000903431 0.124568 0.083255 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 989 1039 0.0719154 -3.09438 0.0893046 0.0646731 -0.00242078 -0.0329685 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1039 1040 6.08795 -0.0407294 -0.313913 0.0222579 0.131683 -0.00795161 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 990 1040 -0.0840367 -3.13153 -0.168456 0.0569444 0.00405093 -0.0472401 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1040 1041 6.17816 0.0865528 -0.32067 0.019615 0.119353 0.0803474 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 991 1041 -0.0433143 -3.24167 0.0373899 0.0550988 -0.00967664 0.0097021 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1041 1042 6.0294 0.0910283 -0.423507 -0.00225374 0.130097 0.0364678 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 992 1042 -0.032313 -3.10775 -0.0399503 0.0689362 0.00230051 0.0722558 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1042 1043 6.08031 0.174105 -0.491993 0.00980618 0.125089 0.0206214 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 993 1043 -0.0450076 -3.17491 -0.232357 0.0727028 -0.00269359 0.0275724 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1043 1044 5.92115 -0.0679761 -0.327502 0.000636537 0.123108 0.0508335 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 994 1044 0.0924275 -3.24373 -0.0502466 0.0660651 -0.00548627 0.0123695 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1044 1045 6.11748 -0.139381 -0.265619 0.0101849 0.120455 0.0145643 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 995 1045 0.0513226 -3.13533 0.11357 0.0627962 -0.00631016 0.00366889 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1045 1046 6.07842 0.14253 -0.318501 0.00492996 0.133787 0.0794774 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 996 1046 -0.12181 -3.10575 0.0530604 0.0518041 0.0130986 -0.00827446 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1046 1047 6.25197 -0.00353764 -0.211457 0.0179816 0.132517 0.0865781 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 997 1047 0.0468625 -2.92249 -0.190572 0.0834802 0.00338914 0.011461 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1047 1048 6.14763 0.0153264 -0.29719 -0.00444939 0.148724 0.0746292 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 998 1048 0.158801 -3.07445 -0.0622193 0.0474084 -0.0136047 0.00203594 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1048 1049 6.26747 0.0405014 -0.23807 -0.00773223 0.113679 -0.0287896 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 999 1049 0.0872764 -3.03741 -0.0709993 0.050718 0.0125808 -0.000447079 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1049 1050 6.19465 0.0756759 -0.388615 0.019697 0.118971 0.0466244 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1000 1050 0.0364527 -3.06329 -0.230868 0.0416661 -0.00739203 -0.0276971 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1050 1051 5.98696 -0.187737 -0.236546 -0.0144769 0.127957 0.0295118 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1001 1051 -0.017474 -3.08181 -0.291564 0.0513922 0.00458928 0.0742654 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1051 1052 6.21685 0.0684367 -0.35136 0.00336755 0.12926 0.0740847 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1002 1052 -0.243078 -2.88971 -0.220245 0.0526813 -0.000596104 0.0386078 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1052 1053 5.82945 -0.131538 -0.359098 -0.00297047 0.117403 -0.00665205 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1003 1053 0.160787 -3.1623 0.00306187 0.0726408 -0.00643517 -0.0305586 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1053 1054 6.108 0.0588155 -0.362254 0.00406484 0.126868 0.117953 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1004 1054 0.0172477 -3.13248 -0.0673503 0.0714904 -0.00114416 0.0507116 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1054 1055 6.03233 -0.0878955 -0.43975 0.00190804 0.113205 -0.0116043 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1005 1055 0.00300913 -3.08044 -0.188548 0.0638552 0.00309908 0.0739211 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1055 1056 6.09999 -0.159129 -0.463801 0.00166706 0.120228 0.0706548 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1006 1056 -0.165673 -3.03641 -0.0542256 0.0707612 -0.004204 0.00653362 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1056 1057 6.14705 -0.0628454 -0.38181 0.0249239 0.133412 0.0145723 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1007 1057 -0.0855289 -3.04582 -0.110658 0.0414245 0.00401868 -0.0614075 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1057 1058 6.01423 0.11765 -0.295349 0.0181719 0.136629 0.0105968 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1008 1058 -0.107003 -3.13213 -0.186061 0.0730631 -0.000571837 0.0284418 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1058 1059 6.27957 0.0556596 -0.31728 0.0140392 0.120582 0.0386207 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1009 1059 -0.0528766 -3.05043 -0.152313 0.0479548 0.014155 -0.00409452 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1059 1060 6.06892 0.092216 -0.491312 0.0164436 0.11161 0.00809407 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1010 1060 -0.124881 -2.98574 0.0201914 0.0594855 0.0108129 -0.0874743 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1060 1061 6.12134 -0.0398637 -0.421935 0.00423477 0.116186 0.055598 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1011 1061 0.00912172 -3.15744 -0.0800272 0.0467645 -0.00975609 -0.0415492 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1061 1062 6.09705 0.167517 -0.460076 0.00967046 0.137158 -0.00784866 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1012 1062 0.267354 -2.92757 0.107772 0.0601418 -0.00422359 -0.061707 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1062 1063 6.19134 0.0928044 -0.500595 0.00885297 0.108547 0.0267062 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1013 1063 -0.0857843 -3.20239 -0.0271958 0.0655521 0.0127662 0.0417003 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1063 1064 6.00901 -0.0938813 -0.257377 0.00208365 0.127158 0.0639285 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1014 1064 0.00202644 -3.35284 -0.0148275 0.0458927 -0.0145341 -0.0248595 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1064 1065 6.13156 0.137904 -0.402413 -0.0168735 0.123365 0.0307077 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1015 1065 -0.0557483 -3.26206 -0.0966394 0.0552693 -0.00597417 -0.00234309 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1065 1066 5.8166 -0.0438778 -0.317794 -0.00066452 0.132376 -0.0671454 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1016 1066 -0.0688921 -3.10151 -0.0695297 0.0453311 -0.00733452 -0.0451296 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1066 1067 6.1669 0.0253997 -0.260424 0.00961925 0.114448 -0.0185609 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1017 1067 -0.0400608 -2.96519 -0.0261511 0.0563196 0.014745 -0.019549 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1067 1068 6.09435 0.22418 -0.244341 0.00270531 0.102024 0.0201089 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1018 1068 -0.0140463 -3.22367 -0.135489 0.05285 0.00648796 0.0143812 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1068 1069 6.03226 -0.0692829 -0.487135 0.00987708 0.131153 0.0231141 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1019 1069 -0.00889372 -3.11194 -0.00547035 0.0903767 0.00175286 0.0123234 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1069 1070 6.21386 -0.0629814 -0.417564 -0.00114716 0.125351 0.0341042 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1020 1070 0.119134 -3.10407 -0.0784602 0.0515334 0.00128572 0.0698075 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1070 1071 6.16485 -0.104516 -0.265045 -0.00331851 0.133338 0.0288868 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1021 1071 0.0445396 -2.89137 -0.0238769 0.0766207 0.00710428 0.0413658 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1071 1072 6.05964 -0.0833047 -0.390707 -0.00327706 0.126676 -0.0209907 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1022 1072 0.0405111 -3.13078 -0.132292 0.041961 0.00690881 -0.0723588 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1072 1073 6.07877 -0.0476411 -0.302659 0.00340964 0.119548 0.00585338 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1023 1073 0.032551 -3.02805 -0.0452315 0.0581739 -0.00955866 -0.0339816 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1073 1074 6.0445 -0.00762603 -0.495496 0.0190381 0.118102 0.0296039 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1024 1074 -0.197006 -3.07459 -0.118671 0.0672448 0.00306581 -0.0120736 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1074 1075 6.12225 0.368408 -0.592146 0.00265349 0.120887 0.0266601 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1025 1075 0.0554664 -3.11073 0.109185 0.0622849 -0.0036393 0.0621697 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1075 1076 6.05755 -0.021068 -0.485975 -0.000560902 0.126397 -0.0136746 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1026 1076 -0.0760813 -3.03559 -0.119675 0.0685157 0.00755513 0.0119111 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1076 1077 6.31811 0.0947494 -0.306213 0.00184166 0.111588 0.00296177 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1027 1077 -0.166508 -3.09051 -0.0148712 0.0595456 -0.0121267 0.050153 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1077 1078 6.15222 0.112098 -0.523338 0.0125899 0.115575 0.0375225 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1028 1078 -0.0133315 -3.05111 -0.206278 0.0772941 0.0116131 -0.0555171 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1078 1079 6.17755 0.12819 -0.189973 0.000843511 0.116096 0.00879123 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1029 1079 -0.0219378 -3.04446 -0.102629 0.0636134 0.00783117 -0.00159266 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1079 1080 5.95207 0.0939997 -0.368303 -0.00750328 0.121706 0.100502 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1030 1080 -0.0221662 -3.00588 0.0265332 0.0695503 0.0132984 -0.0348094 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1080 1081 6.05785 0.0426549 -0.326202 -0.00984398 0.118128 -0.00632891 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1031 1081 -0.143291 -3.18771 -0.242497 0.056048 0.00119822 0.0461257 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1081 1082 6.20024 -0.206181 -0.499325 -0.00457969 0.119587 -0.00198287 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1032 1082 -0.0884373 -3.14039 -0.00446338 0.0566139 0.000695243 -0.0213606 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1082 1083 6.24174 0.152607 -0.390138 -0.00802617 0.122366 0.0956332 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1033 1083 0.0597932 -2.98147 -0.125644 0.0516008 0.0118111 -0.00173589 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1083 1084 6.06745 0.08815 -0.402558 0.0034183 0.0941492 0.0322419 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1034 1084 0.0236397 -3.03106 -0.303444 0.0619699 0.00625717 -0.0188944 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1084 1085 6.18171 0.17784 -0.444196 -0.00483133 0.131197 0.0321817 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1035 1085 0.063638 -3.10132 -0.0102661 0.0604996 0.00226534 -0.0351615 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1085 1086 6.2606 0.147161 -0.343331 0.0120022 0.121572 0.0256834 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1036 1086 -0.0182845 -3.16163 -0.0492317 0.0627212 0.00763229 -0.0292377 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1086 1087 6.00922 0.0565105 -0.400682 -0.0164795 0.118815 0.0544954 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1037 1087 -0.0705535 -2.90117 0.0136399 0.0528724 -0.00757374 0.000569421 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1087 1088 6.01097 0.00313886 -0.305999 0.0211516 0.126623 -0.0111902 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1038 1088 0.0791077 -2.93616 -0.0308763 0.0743151 -0.0165291 -0.0371178 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1088 1089 6.16575 -0.171466 -0.550936 0.00719995 0.111632 0.0238555 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1039 1089 -0.103707 -3.04427 -0.113873 0.0703263 0.00028678 -0.0362127 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1089 1090 6.21322 -0.00849605 -0.355218 0.00706184 0.117116 -0.0180281 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1040 1090 -0.0173157 -3.0989 -0.157895 0.0567648 -0.0113957 -0.00613244 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1090 1091 6.26951 -0.0628921 -0.299126 0.0140689 0.116714 0.0338002 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1041 1091 -0.0740555 -3.10747 -0.126066 0.0525692 0.0115862 -0.0223028 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1091 1092 6.28048 0.148534 -0.239882 0.00610426 0.113751 -0.000840489 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1042 1092 0.104559 -3.06209 0.111713 0.0838355 -0.00447292 0.0242562 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1092 1093 6.02017 0.0976359 -0.377826 -0.00156448 0.11978 0.0440217 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1043 1093 -0.0955397 -3.19568 -0.0795252 0.0785121 0.00964025 0.0377329 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1093 1094 5.97986 0.0143573 -0.433581 0.0079164 0.137914 0.109198 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1044 1094 -0.0650137 -3.05473 -0.0704064 0.0633922 -0.00593448 -0.0496577 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1094 1095 6.15037 0.136784 -0.300618 -0.008954 0.111454 0.0658604 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1045 1095 0.129152 -3.19416 -0.265199 0.0662617 -0.00910922 0.0177384 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1095 1096 6.17229 0.0309696 -0.408303 -0.00419139 0.125479 0.030393 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1046 1096 -0.148981 -3.08871 -0.0483914 0.0850839 0.0186987 -0.023607 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1096 1097 6.2309 -0.140674 -0.511553 -0.00871321 0.136884 -0.0163486 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1047 1097 0.00992533 -3.1456 -0.00346286 0.0513165 0.00933384 0.0524112 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1097 1098 6.00354 -0.119569 -0.219026 -0.0105782 0.118753 -0.0395874 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1048 1098 0.0585119 -3.11981 -0.170435 0.0542401 -0.00340165 -0.0108663 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1098 1099 5.96052 -0.00606136 -0.365239 -0.0100354 0.135354 0.00402471 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1049 1099 -0.0788919 -3.01608 -0.082015 0.0652414 0.00383805 0.0108272 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1099 1100 6.25167 -0.011181 -0.436577 0.0038566 0.130473 0.0502447 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1050 1100 0.0846936 -2.84773 -0.0178092 0.0715169 -0.0159994 -0.079684 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1100 1101 6.28251 0.060292 -0.286956 0.0220496 0.113477 -0.0131819 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1051 1101 0.0292993 -3.19096 -0.0247129 0.0515801 0.0113776 -0.0118587 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1101 1102 6.10196 -0.10118 -0.358981 -0.0187578 0.118576 0.0929051 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1052 1102 0.0542849 -2.80355 -0.005091 0.0498093 -0.0072343 -0.0367911 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1102 1103 6.21236 -0.047097 -0.391111 -0.00644082 0.111769 0.02081 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1053 1103 0.0795033 -2.99578 -0.145515 0.0531904 -0.00182233 0.0220957 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1103 1104 6.14272 0.210213 -0.293225 -0.00246537 0.140693 0.003642 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1054 1104 0.0221612 -3.00317 -0.0829812 0.0481857 -0.00387521 0.0011354 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1104 1105 6.20722 -0.0358492 -0.386077 -0.000974491 0.124548 -0.0195871 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1055 1105 0.0211163 -2.96602 -0.135401 0.0634003 0.0173043 -0.0299232 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1105 1106 6.21492 -0.0181741 -0.468509 -0.00719059 0.112028 -0.0239765 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1056 1106 0.160901 -3.04948 -0.262677 0.0547535 0.00324715 0.0382597 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1106 1107 6.24165 -0.0238348 -0.372464 -0.00279274 0.119885 0.00466365 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1057 1107 -0.00241801 -2.91995 0.0207867 0.0677379 0.0032765 -0.0156418 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1107 1108 6.21019 0.0794247 -0.351371 -0.00242369 0.107898 -0.00418186 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1058 1108 0.0591185 -2.98281 -0.0250635 0.0695111 0.00564023 -0.0877169 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1108 1109 5.93823 -0.00466762 -0.501215 -0.0186952 0.120498 0.0393097 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1059 1109 0.0638423 -3.14503 0.0594812 0.0624415 0.00418805 -0.00882451 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1109 1110 6.17681 -0.0820368 -0.49288 -0.000916301 0.133056 -0.0155687 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1060 1110 0.0901483 -3.19161 -0.217534 0.0491502 0.00153027 -0.0201118 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1110 1111 6.29545 0.0712638 -0.411115 0.0377754 0.113678 0.018377 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1061 1111 0.0732734 -2.94313 -0.196864 0.0625231 0.0154915 -0.050175 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1111 1112 6.06504 0.0138377 -0.485242 0.00170041 0.143767 0.0598643 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1062 1112 -0.043966 -3.08859 0.0557771 0.0736201 -0.000847484 0.00699583 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1112 1113 6.17025 0.0210747 -0.366295 0.00860459 0.126354 0.0615852 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1063 1113 -0.0642777 -3.2544 -0.212404 0.0578576 0.00726952 0.0744094 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1113 1114 6.1543 0.16621 -0.242877 0.00117569 0.118924 -0.0275076 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1064 1114 0.032159 -3.17742 -0.0284652 0.0696175 -0.00245622 -0.0412676 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1114 1115 6.22605 -0.095196 -0.470942 0.0170335 0.130495 0.00650548 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1065 1115 -0.02792 -3.15506 -0.165897 0.0563792 -0.0107167 0.0487689 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1115 1116 6.01358 0.0878971 -0.424228 -0.0166978 0.126216 0.0107246 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1066 1116 0.104795 -3.08425 -0.204007 0.0449939 0.0341304 -0.0514564 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1116 1117 6.16229 0.22305 -0.31995 -0.00150606 0.131846 0.0413941 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1067 1117 -0.158638 -3.09852 -0.0296164 0.0662336 -0.0145423 -0.0504572 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1117 1118 6.16712 0.149935 -0.312976 -0.0113039 0.132253 0.0558755 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1068 1118 -0.111918 -3.16048 -0.105541 0.05971 -0.0114813 0.0145301 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1118 1119 6.34942 0.103401 -0.406601 0.00389863 0.11997 0.0687055 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1069 1119 0.0454455 -3.04932 -0.090615 0.0664826 0.00343029 -0.0935179 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1119 1120 6.08571 0.0943472 -0.265715 0.0112952 0.122013 -0.00596728 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1070 1120 0.0289694 -3.03173 -0.20876 0.0647357 0.00606774 0.086683 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1120 1121 6.00073 -0.0804251 -0.178711 -0.0170954 0.120458 0.124963 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1071 1121 -0.159112 -3.22867 -0.121974 0.0625469 -0.000263131 -0.0143031 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1121 1122 6.06097 -0.0730442 -0.528845 -0.00254867 0.13277 0.0377239 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1072 1122 -0.158343 -2.99913 -0.134118 0.044007 -0.00180094 0.0133859 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1122 1123 6.27635 0.0225442 -0.330146 0.0168033 0.129204 0.015818 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1073 1123 -0.0339182 -3.00933 -0.117717 0.056271 0.00974681 0.0625455 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1123 1124 6.20388 -0.123736 -0.320419 0.0250547 0.128394 -0.00816691 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1074 1124 -0.115012 -3.16768 -0.07791 0.0617937 0.00895912 0.0258813 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1124 1125 6.19488 0.0489028 -0.40507 -0.0220558 0.141578 0.0362234 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1075 1125 -0.0255793 -3.22819 -0.117767 0.0580595 0.00167263 0.0105117 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1125 1126 6.34134 0.0211631 -0.488231 -0.0132564 0.128261 0.0253446 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1076 1126 -0.00893484 -2.96332 0.026229 0.0616841 0.00529419 0.0148742 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1126 1127 6.27149 -0.00500805 -0.2324 0.00735068 0.118331 0.0933392 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1077 1127 0.105186 -2.96758 -0.0759412 0.0640446 0.00878758 0.0212397 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1127 1128 6.05908 0.0801083 -0.328133 -0.00762452 0.131783 0.0517594 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1078 1128 -0.0191909 -2.93195 -0.296513 0.0614619 0.00854899 -0.0013414 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1128 1129 6.06045 0.0970754 -0.257414 0.0121556 0.113352 0.0185225 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1079 1129 -0.00207403 -3.10804 -0.284215 0.0736289 0.00112952 0.00848881 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1129 1130 6.19519 0.023938 -0.465982 0.00604271 0.12612 -0.00431508 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1080 1130 0.0287871 -3.02091 -0.0798066 0.0581025 0.003915 0.0151224 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1130 1131 6.2437 0.00818919 -0.282187 5.06439e-05 0.120334 0.0279945 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1081 1131 -0.01036 -2.95319 -0.267749 0.0665137 0.00313463 0.0353665 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1131 1132 6.17458 -0.157841 -0.456966 0.01145 0.108147 0.0939827 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1082 1132 0.0065057 -3.04553 0.0311802 0.079447 -0.0111594 0.00784671 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1132 1133 5.97333 0.128973 -0.364609 0.00599042 0.137116 0.0531381 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1083 1133 -0.0435569 -3.0335 0.0190937 0.0594872 -0.00491381 0.00369368 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1133 1134 6.29684 0.00526453 -0.371747 0.0131013 0.127585 0.00362231 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1084 1134 -0.0712779 -3.1773 -0.0214954 0.0468121 -0.00589329 0.000670697 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1134 1135 6.33641 -0.158932 -0.206777 -0.00091457 0.132517 0.108933 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1085 1135 0.133739 -3.27775 -0.174547 0.0531023 -0.00393874 -0.0311202 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1135 1136 6.15569 0.0989295 -0.218852 0.000485009 0.124438 -0.0289829 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1086 1136 0.16106 -3.26226 0.0412023 0.0550875 -0.00152333 -0.0633918 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1136 1137 6.19086 -0.290265 -0.400818 0.0232141 0.125976 0.00145055 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1087 1137 0.265508 -3.09031 -0.147831 0.069088 -0.0133488 -0.0353985 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1137 1138 6.10112 0.125422 -0.421247 0.00711764 0.146202 0.0224651 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1088 1138 0.117624 -3.10572 -0.107534 0.0481438 0.0184414 0.0138854 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1138 1139 6.28191 -0.137981 -0.375466 -0.000363153 0.124761 0.0493158 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1089 1139 0.0900041 -3.01079 0.0336033 0.0672826 -0.00538783 -0.0503312 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1139 1140 6.18316 0.0500493 -0.324958 -0.0112912 0.11931 0.0454003 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1090 1140 -0.0123915 -2.98739 -0.0590395 0.0379968 -0.00716509 0.0111404 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1140 1141 6.08349 0.136814 -0.497156 0.0011048 0.119299 0.0229301 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1091 1141 -0.000347532 -2.9763 -0.070558 0.0715813 -0.00247412 0.0476235 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1141 1142 6.155 0.0205256 -0.330061 -0.00213636 0.127456 -0.0252327 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1092 1142 0.0170841 -3.03 -0.00536934 0.0591185 -0.00452181 0.017787 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1142 1143 6.28604 0.025346 -0.421007 -0.0162974 0.121919 0.112466 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1093 1143 0.0794835 -3.01918 -0.0688588 0.0578745 0.0134547 -0.0346294 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1143 1144 6.26062 0.0205431 -0.677658 0.00428368 0.126012 -0.0385355 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1094 1144 0.108576 -3.19047 -0.156856 0.0494548 -0.0163793 0.0102638 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1144 1145 6.24365 -0.0324574 -0.262743 -0.0049103 0.127112 0.00951213 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1095 1145 -0.0581562 -2.90244 0.012481 0.0434028 0.00263195 -0.0287951 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1145 1146 6.20747 -0.0339152 -0.392379 -0.000234102 0.118708 -0.0293292 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1096 1146 0.115824 -3.19631 -0.0213371 0.0421217 -0.00522808 -0.00975261 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1146 1147 6.17383 -0.0545486 -0.330068 0.00652005 0.105633 0.00926072 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1097 1147 0.231058 -2.97191 -0.0633144 0.0554662 0.0120193 0.0251226 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1147 1148 6.19562 -0.0312521 -0.508851 -0.00400235 0.127798 0.0500741 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1098 1148 0.0906347 -3.0823 -0.0654172 0.0671222 -0.00576249 -0.0420048 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1148 1149 6.2634 -0.0914435 -0.49194 -0.000185698 0.126647 0.0596173 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1099 1149 -0.0709827 -2.99242 -0.100519 0.0522911 0.0107663 -0.0665954 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1149 1150 6.20794 0.00706315 -0.366789 0.00491578 0.116074 0.0396255 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1100 1150 -0.217694 -3.0471 -0.241971 0.0595434 -0.00299944 0.0307673 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1150 1151 6.3853 0.0766322 -0.371624 -0.004531 0.115342 0.0513507 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1101 1151 -0.133997 -3.18039 -0.298347 0.0585356 0.00161758 -0.045421 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1151 1152 6.36965 0.00317052 -0.340421 0.00713771 0.131289 0.00930946 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1102 1152 -0.120782 -3.10771 -0.132829 0.0542114 -0.00147593 -0.0292094 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1152 1153 6.25122 0.119082 -0.489597 0.0134678 0.140105 0.0241665 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1103 1153 0.0651546 -3.08526 0.0333165 0.053678 -0.00110048 0.0495263 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1153 1154 6.38591 0.0431815 -0.249205 0.021483 0.128554 0.0183652 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1104 1154 -0.13073 -3.10417 -0.0207559 0.0570843 -0.0033487 0.0265582 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1154 1155 6.22207 -0.126374 -0.551195 0.00632646 0.140176 0.038975 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1105 1155 0.000154459 -3.19468 -0.219612 0.0717736 -0.00997412 -0.0318834 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1155 1156 6.24973 0.0357949 -0.346418 0.00727606 0.107899 -0.026173 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1106 1156 -0.0526983 -3.14509 -0.0514529 0.054524 -0.00459064 0.0115624 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1156 1157 6.28222 0.0285707 -0.466702 -0.00109388 0.119678 -0.00257011 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1107 1157 0.021276 -3.03634 0.0578121 0.0690819 0.00523775 0.0187549 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1157 1158 6.02883 -0.0220242 -0.272902 0.0104637 0.134122 0.0219901 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1108 1158 -0.034091 -3.05927 -0.0180954 0.0409502 0.00491874 0.0411946 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1158 1159 6.25064 0.0633914 -0.346644 0.00177177 0.139352 -0.0448145 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1109 1159 0.0976821 -2.96001 -0.091843 0.0665695 0.00910561 -0.0377344 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1159 1160 6.22868 -0.0403906 -0.411585 -0.0147735 0.121385 0.054934 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1110 1160 -0.0205294 -3.13789 0.114621 0.0592746 -0.000284181 -0.0480345 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1160 1161 6.0705 -0.0717024 -0.375346 -0.00132932 0.104671 -0.0268544 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1111 1161 0.091867 -2.94575 -0.372363 0.0433479 -0.0122475 0.0396798 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1161 1162 6.29081 -0.069955 -0.449193 0.00155694 0.118082 -0.0249379 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1112 1162 0.162605 -3.15417 -0.179408 0.0475352 -0.0104949 -0.0208354 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1162 1163 6.14631 -0.0120103 -0.47997 0.0150382 0.138681 0.0572245 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1113 1163 0.0157016 -3.09259 0.0738619 0.0590827 0.00998473 0.0376913 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1163 1164 6.22764 -3.65271e-05 -0.550282 -0.00710382 0.137956 0.00092898 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1114 1164 0.0998559 -3.04731 -0.27322 0.0331142 0.0156435 -0.0522191 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1164 1165 6.2428 -0.0654257 -0.421962 -0.0123629 0.121843 0.0232916 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1115 1165 0.0358571 -3.03004 -0.157249 0.0444812 -0.00708214 0.0302565 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1165 1166 6.2161 -0.155607 -0.382093 -0.0012638 0.142177 -0.0035467 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1116 1166 0.0257678 -3.09835 -0.0826716 0.0563032 -0.00457881 -0.0166752 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1166 1167 6.15893 -0.0574 -0.40431 -0.00913287 0.127124 -0.0243037 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1117 1167 -0.0353658 -3.05448 -0.151444 0.0510831 0.0157569 -0.0345797 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1167 1168 6.05773 -0.168017 -0.413493 0.00471689 0.108466 -0.0371183 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1118 1168 0.0758524 -2.9502 -0.244958 0.0407956 -0.00395624 -0.0118775 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1168 1169 6.28452 0.000196641 -0.238558 -0.00781353 0.11138 0.00850205 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1119 1169 -0.00501287 -2.75295 -0.2332 0.057217 0.00624272 -0.039381 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1169 1170 6.58885 -0.295857 -0.378598 0.0200237 0.13312 0.0413619 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1120 1170 -0.128876 -3.07645 -0.0519347 0.0510374 0.0017215 0.00370018 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1170 1171 6.3906 -0.0581844 -0.399454 0.0127656 0.126514 -0.00685001 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1121 1171 0.175866 -3.02884 0.142398 0.0517692 0.00542184 -0.0490466 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1171 1172 6.15073 0.102358 -0.410398 -0.000684918 0.121311 -0.0298668 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1122 1172 -0.0466014 -3.01999 -0.124203 0.0654775 0.0162323 -0.0749021 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1172 1173 6.16127 -0.146017 -0.499986 0.0109923 0.117013 -0.00513184 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1123 1173 0.0476419 -2.8824 -0.029238 0.0549883 -0.0191383 0.0143575 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1173 1174 6.22705 0.0784242 -0.488882 0.00798086 0.122065 0.0512638 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1124 1174 0.113472 -3.02205 0.0360127 0.0622727 0.00223291 0.0606059 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1174 1175 6.14964 0.0735096 -0.220936 0.00974938 0.111929 -0.0222428 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1125 1175 0.164588 -2.921 -0.0232025 0.0535143 -0.0112863 -0.0134635 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1175 1176 6.38982 0.0183722 -0.435402 0.00607739 0.126548 0.04336 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1126 1176 -0.067375 -2.962 -0.0608439 0.0350147 -0.00210198 -0.027105 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1176 1177 6.52476 0.0590775 -0.171495 0.0116967 0.139899 -0.0214495 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1127 1177 0.111208 -3.27 -0.00309067 0.0708333 0.00424104 -0.0298877 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1177 1178 6.22519 0.00334483 -0.524122 -0.022457 0.118181 0.00798823 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1128 1178 0.0696515 -2.92745 -0.232218 0.0596541 -0.0212403 0.0446132 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1178 1179 5.98156 -0.188664 -0.281838 0.0214618 0.119389 -0.0218256 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1129 1179 -0.0872156 -3.00687 -0.242848 0.0509584 -0.00114863 0.00146875 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1179 1180 6.12504 0.0176742 -0.511712 0.0110223 0.142761 0.0227157 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1130 1180 0.135662 -2.98974 -0.166074 0.0676836 -0.00142452 0.0746129 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1180 1181 6.10667 -0.0374723 -0.241947 0.00594995 0.118198 -0.00308398 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1131 1181 0.0126317 -3.00361 0.0692822 0.0413905 -0.0175662 0.0494715 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1181 1182 6.35836 -0.0447324 -0.440683 -0.00323157 0.123551 -0.0531008 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1132 1182 0.087144 -3.00094 0.00257029 0.0414581 0.00552438 -0.00460815 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1182 1183 6.31991 0.0903055 -0.108557 -0.0037222 0.129444 -0.0201744 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1133 1183 0.0226019 -3.04873 -0.299544 0.0739847 0.00325843 0.0105872 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1183 1184 6.3725 0.181198 -0.36497 0.00450368 0.115141 -0.03112 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1134 1184 -0.140581 -3.05227 0.0454369 0.0682553 -0.00626141 -0.0614491 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1184 1185 6.1966 0.201242 -0.518595 0.00328037 0.120757 -0.0282697 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1135 1185 0.0316004 -2.98084 -0.193694 0.0548329 -0.00660026 0.00418652 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1185 1186 6.23127 -0.0799887 -0.438554 0.0155449 0.114729 0.0382819 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1136 1186 0.0678883 -3.03565 -0.13131 0.047952 -0.00323373 0.0268506 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1186 1187 6.14199 -0.0961718 -0.446934 0.0105936 0.11905 0.0168399 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1137 1187 -0.0966377 -3.0895 -0.144126 0.0667826 -0.00180578 -0.0124919 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1187 1188 6.20196 -0.128109 -0.216675 0.00196043 0.111597 -0.00616853 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1138 1188 -0.191259 -3.12618 -0.287744 0.0659891 0.00926523 -0.0576857 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1188 1189 6.46824 -0.0118163 -0.309085 -0.00168811 0.119072 -0.0511947 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1139 1189 0.120915 -2.91691 -0.0350008 0.0638543 0.0088096 -0.000771982 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1189 1190 6.21507 -0.071789 -0.293747 -0.00148837 0.125161 0.0211515 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1140 1190 0.11299 -3.07753 -0.0105921 0.0485608 0.00893849 0.115698 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1190 1191 6.3815 0.011158 -0.191186 0.00603326 0.12735 -0.0131462 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1141 1191 0.0181987 -3.08558 0.044592 0.0799863 0.00623674 -0.0131192 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1191 1192 6.14022 -0.0361197 -0.317708 0.00276229 0.123296 0.0153926 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1142 1192 0.0601452 -3.00042 0.150736 0.0525887 -0.00807706 -0.0304554 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1192 1193 6.21883 0.0924226 -0.388814 -0.00105321 0.112256 -0.0225528 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1143 1193 0.0722748 -3.04419 -0.145982 0.0479098 -0.00529585 -0.00320511 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1193 1194 6.2813 -0.0791019 -0.302846 -0.00892097 0.113642 0.0173518 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1144 1194 0.0237231 -3.05141 -0.215397 0.0497263 -0.00440838 0.0326057 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1194 1195 6.23938 -0.0764255 -0.319361 -0.000338102 0.130198 0.0417771 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1145 1195 0.028394 -3.23374 -0.246211 0.0595846 -0.0149741 0.0962783 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1195 1196 6.25058 -0.199206 -0.369816 -0.00540097 0.130799 0.0717416 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1146 1196 0.223023 -3.01226 0.118686 0.0764673 -0.00628123 -0.0159071 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1196 1197 6.26815 -0.176915 -0.460459 -0.00143768 0.13026 0.0716267 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1147 1197 0.0295023 -2.99339 -0.110198 0.0644165 -0.0168296 0.0253937 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1197 1198 6.15318 0.00500709 -0.408395 0.0197267 0.120722 0.00674476 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1148 1198 -0.0636762 -3.05069 0.0395257 0.0639131 -0.0143176 -0.0942336 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1198 1199 6.24575 0.052209 -0.510219 0.0183878 0.129016 0.027767 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1149 1199 0.0128021 -3.04374 -0.148374 0.0670007 0.00461108 -0.0906184 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1199 1200 6.26576 -0.0804633 -0.345597 0.0028857 0.145858 -0.0348468 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1150 1200 0.0837259 -3.23437 -0.161845 0.047648 -0.00239266 -0.0217948 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1200 1201 6.2058 0.00716553 -0.407173 -0.0131567 0.115069 -0.0158414 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1151 1201 -0.00140064 -3.01718 -0.0967987 0.0579447 -0.00919273 0.00184034 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1201 1202 6.21133 -0.199235 -0.226973 -0.0023761 0.142525 -0.0835644 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1152 1202 0.0271031 -3.06013 0.00867464 0.0782588 0.00743101 -0.000629788 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1202 1203 6.21438 0.0122662 -0.380782 0.00530027 0.12915 0.00691982 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1153 1203 0.0217358 -2.96145 -0.106814 0.0601789 0.0153562 0.00271351 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1203 1204 6.21195 -0.0819153 -0.444214 0.0157669 0.116926 -0.034367 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1154 1204 0.0270931 -2.91063 0.0451615 0.0767124 -0.00402041 -0.014525 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1204 1205 6.16872 -0.12651 -0.42569 -0.0111502 0.126023 0.0817227 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1155 1205 0.0800109 -2.89701 -0.183108 0.0709816 -0.0114715 0.0727754 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1205 1206 6.21633 0.111715 -0.359401 0.00639357 0.116679 -0.0216481 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1156 1206 -0.0248295 -3.01964 -0.0582447 0.0464199 -0.00723046 -0.0306108 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1206 1207 6.32873 0.109302 -0.395666 0.0108302 0.106908 -0.0123529 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1157 1207 0.113841 -3.10738 -0.114207 0.0582474 0.0112536 -0.0138955 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1207 1208 6.29206 -0.212852 -0.281398 0.00323675 0.10375 -0.0425858 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1158 1208 0.038877 -2.98515 -0.256207 0.0707347 -0.0252301 0.0407279 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1208 1209 6.45017 -0.034892 -0.593871 -0.00506067 0.139349 -0.00049116 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1159 1209 0.0217916 -3.14152 0.148494 0.0447892 -0.00411327 0.0538952 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1209 1210 6.32709 -0.133107 -0.460409 -0.00244919 0.130486 -0.00112364 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1160 1210 0.043156 -3.04312 -0.0215019 0.074753 -0.00227475 -0.0331218 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1210 1211 6.21435 -0.0563002 -0.193585 -0.0104876 0.118732 0.0250732 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1161 1211 -0.160744 -2.9101 -0.152645 0.054119 -0.00484394 -0.0636794 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1211 1212 6.40085 -0.126828 -0.394095 0.00722234 0.127954 -0.0237984 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1162 1212 -0.0771665 -2.93696 -0.078103 0.0605476 -0.00554644 -0.000576041 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1212 1213 6.29461 -0.0960924 -0.113984 -0.00180288 0.135772 0.0110639 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1163 1213 0.0374038 -2.82418 -0.000826757 0.0613369 -0.0078006 0.00385694 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1213 1214 6.03313 0.0836024 -0.478308 0.00181283 0.119755 -0.00353573 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1164 1214 -0.230059 -3.00784 7.51296e-05 0.0581886 0.00392659 -0.0563753 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1214 1215 6.36117 -0.0184892 -0.427555 0.00482647 0.106701 0.0017714 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1165 1215 0.033549 -2.82354 -0.0558731 0.0669523 0.00443503 0.0254013 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1215 1216 6.19065 -0.130134 -0.622243 0.012899 0.127552 -0.0340309 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1166 1216 -0.00977411 -3.07625 -0.188491 0.0722305 0.018588 -0.0409259 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1216 1217 6.19733 -0.102603 -0.313682 0.00579556 0.13399 0.0234923 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1167 1217 0.0216891 -2.93679 -0.0716218 0.0786563 0.00765587 -0.023588 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1217 1218 6.17407 -0.126553 -0.298197 0.000179622 0.133641 -0.0346398 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1168 1218 0.0706638 -3.06932 -0.137611 0.061247 -0.00304523 -0.0114267 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1218 1219 6.31511 -0.126804 -0.414715 0.00180041 0.132426 0.0355416 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1169 1219 0.156672 -3.09943 -0.0141817 0.0699514 0.0115585 -0.031943 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1219 1220 6.39377 -0.288752 -0.304232 -0.00787355 0.120574 -0.0622604 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1170 1220 0.00982461 -2.92941 -0.0510959 0.0571931 -0.00887197 0.01336 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1220 1221 6.39289 -0.0663798 -0.305302 -0.0169902 0.136597 -0.0275191 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1171 1221 0.0582776 -3.09627 -0.169073 0.0682808 -0.00669876 -0.101574 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1221 1222 6.28966 -0.00119897 -0.270048 0.0162912 0.125255 -0.0405335 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1172 1222 0.104497 -3.0923 -0.0486395 0.0586285 -0.0102709 0.0263689 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1222 1223 6.17122 0.0132848 -0.391997 -0.00234707 0.116056 0.00404941 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1173 1223 0.0400036 -3.0597 -0.00726114 0.0701801 0.00448127 -0.0461388 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1223 1224 6.29206 -0.0198421 -0.189114 0.00439959 0.120182 0.026061 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1174 1224 0.0599887 -3.19008 0.0384103 0.0601458 -0.0156649 -0.0061596 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1224 1225 6.28551 0.118613 -0.317331 0.0056966 0.120361 0.00823602 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1175 1225 0.0836869 -2.95782 -0.264283 0.0390534 0.00488864 -0.0085675 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1225 1226 6.35893 0.0761398 -0.14686 -0.00129582 0.113948 0.0210617 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1176 1226 0.0365858 -2.99531 -0.0278675 0.0464319 -0.00479809 0.0340089 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1226 1227 6.29498 -0.0588479 -0.4579 -0.0158094 0.111851 0.00251321 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1177 1227 -0.0305253 -3.07889 -0.18549 0.071092 -0.00919756 -0.0354398 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1227 1228 6.03972 -0.00553889 -0.459341 0.0131592 0.135019 -0.00939779 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1178 1228 -0.0319369 -3.01015 -0.177579 0.0662978 -0.00281894 0.0492645 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1228 1229 6.05532 -0.0844357 -0.300037 0.00958365 0.130753 -0.0491874 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1179 1229 -0.0523832 -2.98778 -0.239663 0.0627745 -0.00669453 -0.0837139 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1229 1230 6.3632 -0.0759518 -0.388078 -0.0199902 0.113556 0.0185039 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1180 1230 -0.0983646 -2.9026 0.12701 0.065465 5.19111e-05 0.0157345 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1230 1231 6.22883 0.0639962 -0.388497 0.00793759 0.124069 -0.0269226 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1181 1231 -0.00253273 -3.13452 -0.205119 0.0540255 0.0107875 0.0663391 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1231 1232 6.15602 0.048115 -0.397565 -0.0170432 0.118064 0.00999427 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1182 1232 -0.123887 -3.1491 0.0293308 0.0629327 0.0131407 0.000552936 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1232 1233 6.17968 -0.0168155 -0.406422 0.0178193 0.121558 -0.0298427 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1183 1233 0.0530003 -3.14802 -0.0660283 0.057909 0.0019715 0.0587453 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1233 1234 6.31784 0.019186 -0.279467 0.00599333 0.128451 -0.0227361 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1184 1234 -0.0920964 -3.03163 -0.0502112 0.068293 -0.0227271 0.0301324 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1234 1235 6.18515 -0.0802051 -0.231245 -0.00572597 0.148774 -0.0115332 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1185 1235 0.150772 -3.17657 0.0119297 0.0588427 -0.0153285 -0.0323586 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1235 1236 6.18542 -0.182362 -0.404059 0.00192593 0.146087 -0.00738 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1186 1236 -0.0118933 -3.07448 -0.216914 0.052578 0.00304382 -0.0242472 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1236 1237 6.22582 -0.0130983 -0.631928 -0.000336692 0.130282 0.0108888 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1187 1237 0.107145 -3.11149 0.0407158 0.0719982 0.0120477 -0.0186877 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1237 1238 6.22747 0.0813933 -0.36263 0.0124855 0.133053 -0.00511183 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1188 1238 0.0785587 -3.07704 -0.0334033 0.0596239 0.0272998 -0.0548149 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1238 1239 6.13728 -0.245842 -0.469497 -0.00427778 0.118902 0.0466426 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1189 1239 0.057874 -3.01272 -0.0126197 0.0757248 -0.0150501 0.063832 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1239 1240 6.43442 0.0421073 -0.445315 -0.00501035 0.122143 -0.0453351 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1190 1240 0.00429653 -3.0416 -0.15987 0.0619307 -0.000361436 0.0533429 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1240 1241 6.22238 0.00147875 -0.419885 0.000407927 0.106906 0.0127659 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1191 1241 -0.153794 -3.16575 -0.134849 0.0559876 0.0122063 0.0450317 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1241 1242 6.3993 0.0521169 -0.274175 0.00375655 0.118329 -0.0649456 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1192 1242 -0.0535129 -3.01837 -0.0370581 0.0476833 -0.0033379 0.0754286 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1242 1243 6.33238 0.0638039 -0.303752 -0.00148295 0.119543 0.053673 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1193 1243 -0.0321359 -3.04146 -0.171921 0.0740651 -0.0150853 -0.0420449 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1243 1244 6.2392 -0.35763 -0.230175 0.0217479 0.138351 -0.0987499 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1194 1244 0.213947 -3.15164 -0.0665557 0.0535713 0.00134492 0.0123857 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1244 1245 6.19106 -0.00378847 -0.528655 0.0127252 0.134084 0.0853756 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1195 1245 -0.0477612 -2.98379 -0.224037 0.0444271 0.00274965 0.0276601 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1245 1246 6.29399 0.0514532 -0.393738 0.00260047 0.132047 -0.0760102 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1196 1246 -0.0851834 -3.07162 -0.135769 0.0686547 -0.00424456 -0.0428751 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1246 1247 6.33133 -0.108199 -0.230448 -0.00960094 0.117035 -0.0188169 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1197 1247 -0.196691 -3.20303 -0.125991 0.0617405 0.00402568 -0.00692368 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1247 1248 6.18836 -0.026359 -0.419592 0.00541732 0.140542 -0.0312918 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1198 1248 -0.150325 -2.90899 0.0488011 0.0556008 -0.000482173 0.0402078 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1248 1249 6.25769 -0.0970828 -0.322165 0.0124265 0.141384 -0.0427235 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1199 1249 0.0185902 -3.19486 -0.0656763 0.0770903 -0.0181362 -0.00148543 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1249 1250 6.2899 -0.116221 -0.353315 0.00520953 0.122698 -0.0454123 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1200 1250 0.0357137 -3.20493 -0.0478291 0.0582689 -0.000781128 -0.0243026 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1250 1251 6.12708 -0.158827 -0.517068 0.0107317 0.131897 0.0286125 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1201 1251 -0.200729 -2.95837 -0.0138394 0.0573847 -0.00546167 -0.00537273 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1251 1252 6.27115 -0.0676382 -0.360185 0.00527464 0.127017 0.00330841 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1202 1252 0.0326011 -3.11654 -0.0152223 0.0602674 0.00980507 -0.0372124 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1252 1253 6.1248 -0.147014 -0.489388 0.0091367 0.119432 -0.00173097 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1203 1253 -0.0285094 -3.12084 -0.182164 0.0704937 -0.014826 0.0258192 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1253 1254 6.53703 0.0602544 -0.456811 0.00528208 0.126167 -0.00356809 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1204 1254 0.0110536 -3.01092 0.027117 0.0572131 -0.0150525 -0.0461112 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1254 1255 6.33501 0.016488 -0.398003 -0.00296916 0.114376 -0.0320971 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1205 1255 0.0674776 -3.06268 -0.0976775 0.0645557 0.00949903 0.0161793 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1255 1256 6.14413 -0.18662 -0.551819 -0.00269528 0.124437 0.0352449 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1206 1256 -0.0196083 -2.9626 -0.153325 0.0729159 0.00158927 0.0229019 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1256 1257 6.55898 0.051227 -0.377206 0.0173017 0.120196 -0.0369111 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1207 1257 0.0859312 -3.26951 -0.0912336 0.0747766 0.00101945 -0.0106442 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1257 1258 6.21983 -0.122294 -0.398302 0.00658924 0.127051 0.039338 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1208 1258 -0.0147072 -3.12703 -0.0531484 0.0540965 0.0211755 0.0722214 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1258 1259 6.45607 0.0608365 -0.660542 -0.0158525 0.138364 -0.0706216 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1209 1259 -0.014849 -3.08558 -0.149916 0.07215 0.00711505 -0.0512541 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1259 1260 6.20101 -0.203207 -0.363907 0.00472023 0.132387 -0.0243728 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1210 1260 0.0938793 -3.08888 -0.0800416 0.060821 0.0106298 0.0195448 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1260 1261 6.35532 0.104986 -0.260977 -0.00445762 0.133627 -0.0307316 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1211 1261 0.0756502 -3.09672 0.0478999 0.0602605 0.0178682 -0.032861 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1261 1262 6.3133 -0.0197678 -0.442567 -0.00698201 0.126456 -0.0268019 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1212 1262 -0.0436352 -3.17113 -0.0700736 0.0397673 0.00439854 0.00182757 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1262 1263 6.20818 -0.255142 -0.269164 -0.000876024 0.104709 -0.00241014 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1213 1263 -0.0794503 -3.06742 -0.191774 0.0457172 0.000594096 0.00614631 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1263 1264 6.3877 -0.0229373 -0.413832 0.00763503 0.12965 0.0449614 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1214 1264 0.137458 -3.09804 -0.143777 0.0673827 -0.00395199 -0.0903852 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1264 1265 6.05697 -0.00198107 -0.408921 0.00411694 0.128608 -0.0538856 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1215 1265 -0.12901 -3.00058 -0.155794 0.056092 -0.015383 -0.0232422 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1265 1266 6.28397 -0.153569 -0.664427 0.00553475 0.117594 0.00342066 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1216 1266 0.19784 -2.96466 -0.0681702 0.0575392 -0.0165516 0.043202 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1266 1267 6.24397 -0.120219 -0.435927 0.00103501 0.140058 0.0291781 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1217 1267 0.009327 -3.11755 -0.187005 0.0640473 -0.00614662 -0.015543 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1267 1268 6.30926 -0.150044 -0.303697 -0.000639542 0.110922 -0.0299466 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1218 1268 -0.216884 -3.15929 -0.000483977 0.0705086 -0.0103581 -0.0363552 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1268 1269 6.29611 -0.00343735 -0.285131 -0.00477395 0.130331 -0.0146041 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1219 1269 -0.0404176 -3.01787 -0.0454893 0.0635019 0.00881953 0.0126743 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1269 1270 6.22615 0.10802 -0.349673 -0.00346955 0.122879 -0.0236909 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1220 1270 -0.0343912 -2.85548 0.0651266 0.0871021 -0.00707767 -9.66944e-05 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1270 1271 6.36892 -0.235919 -0.351455 -0.00792541 0.131043 0.0215698 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1221 1271 0.0500387 -3.16555 -0.0646421 0.0629708 -0.0189852 -0.0328915 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1271 1272 6.27609 0.0295116 -0.429726 0.00057528 0.131179 -0.0342096 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1222 1272 -0.0950962 -3.27799 -0.034505 0.048752 -0.0108364 -0.00564083 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1272 1273 6.35224 -0.0636227 -0.390599 0.00579051 0.130529 -0.0520118 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1223 1273 0.000903979 -3.12157 -0.143615 0.0746695 0.00215029 0.0254664 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1273 1274 6.15911 -0.164483 -0.555666 0.00374065 0.129338 0.0120567 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1224 1274 0.103299 -2.88434 0.089176 0.0548347 -0.00954624 -0.025369 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1274 1275 6.28843 -0.127801 -0.507534 -0.00844453 0.145672 -0.0329174 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1225 1275 -0.0430658 -3.02258 -0.326879 0.0463749 -0.00429992 -0.0334999 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1275 1276 6.2427 0.0626399 -0.3638 0.0023189 0.103687 -0.0227484 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1226 1276 0.131429 -3.06407 -0.116871 0.057516 0.00416119 0.0918204 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1276 1277 6.17248 -0.0642882 -0.306885 0.0170405 0.124522 -0.0382094 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1227 1277 0.0874076 -3.00898 -0.201226 0.051516 -0.00453837 0.0394725 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1277 1278 6.11498 -0.0413086 -0.456354 0.0112505 0.126034 -0.0217124 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1228 1278 0.0221527 -2.92567 -0.00606727 0.061344 0.0238919 0.0231577 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1278 1279 6.25378 -0.174784 -0.257661 -0.00636555 0.123086 -0.11108 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1229 1279 -0.0827371 -3.1309 -0.126949 0.0672071 -1.52551e-05 -0.0230076 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1279 1280 6.17019 0.0616008 -0.393819 0.00608905 0.135674 0.0209437 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1230 1280 -0.00340917 -3.02148 -0.128066 0.0585612 -0.0233853 -0.00412157 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1280 1281 6.18631 -0.0294208 -0.500332 -0.000119226 0.124411 -0.0331476 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1231 1281 -0.0597199 -3.02169 0.0538403 0.0825918 0.000621827 -0.0493559 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1281 1282 6.16046 -0.152861 -0.463147 -0.00710748 0.119054 -0.0234503 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1232 1282 0.00633811 -3.18101 -0.128797 0.0678917 -0.0023235 0.0314107 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1282 1283 6.48933 -0.114148 -0.558952 0.016254 0.132427 0.00568016 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1233 1283 0.123263 -2.99847 0.0159669 0.0498338 -0.0106584 -0.0856789 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1283 1284 6.23021 0.0689084 -0.49952 0.00108541 0.123661 -0.0589047 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1234 1284 0.058116 -2.96013 -0.118725 0.0784062 0.00302203 0.0418499 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1284 1285 6.21662 -0.0675519 -0.509614 -7.74085e-06 0.135943 0.0514599 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1235 1285 -0.0321683 -3.14952 -0.17281 0.0589978 0.00494735 -0.00149692 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1285 1286 6.24696 -0.00355016 -0.421317 -0.0101002 0.13188 0.0551212 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1236 1286 -0.0432638 -2.92605 -0.126502 0.0600392 -0.00353916 -0.111385 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1286 1287 6.27844 -0.125261 -0.484204 -0.000469104 0.116518 0.00967152 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1237 1287 -0.164066 -3.11587 -0.138526 0.0459771 0.0103624 0.0386395 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1287 1288 6.30194 -0.175161 -0.519588 0.00570471 0.130042 0.00483855 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1238 1288 0.0922468 -3.03399 0.0613566 0.0513318 0.00111965 0.0255852 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1288 1289 6.15168 0.185523 -0.541771 0.0102575 0.127273 -0.0232311 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1239 1289 -0.0299831 -3.07901 -0.380572 0.0637487 0.000762412 0.0245203 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1289 1290 6.06952 -0.136027 -0.407924 -0.00596985 0.121079 -0.00770528 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1240 1290 0.0548115 -3.01175 -0.0288549 0.074494 -0.0253328 0.0153122 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1290 1291 6.16751 -0.0684213 -0.49552 0.00222471 0.118259 0.0334444 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1241 1291 0.0094919 -3.12566 -0.139396 0.0606138 0.000236116 0.0242394 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1291 1292 6.38761 -0.0557133 -0.479586 -0.00784479 0.11649 -0.0644483 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1242 1292 -0.0838546 -3.10407 -0.0704546 0.0654677 -0.0170895 -0.00324016 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1292 1293 6.09212 -0.171625 -0.299539 0.0105154 0.141035 -0.0409676 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1243 1293 0.286475 -3.11071 -0.151375 0.0663687 -0.00959548 -0.0285603 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1293 1294 6.18646 -0.154189 -0.195278 -0.0146626 0.115924 -0.0642156 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1244 1294 -0.0813753 -3.09128 -0.0170196 0.0792947 -0.0017218 0.0128393 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1294 1295 6.24633 -0.0847706 -0.482392 0.016668 0.131099 0.0163391 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1245 1295 0.0220437 -3.08965 -0.243809 0.0532947 0.00688378 -0.00718575 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1295 1296 6.26818 -0.146763 -0.431497 0.00448523 0.124349 -0.00751718 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1246 1296 0.1711 -3.22702 -0.229123 0.0558606 -0.00196703 0.0148428 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1296 1297 6.16198 -0.0799677 -0.242041 0.00209855 0.112333 -0.0512353 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1247 1297 -0.109196 -3.17172 -0.339867 0.0604321 0.0158696 -0.00205957 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1297 1298 6.09268 -0.137636 -0.358679 0.0061355 0.127449 -0.0124003 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1248 1298 0.102301 -2.80005 -0.0583969 0.0782237 -0.00766947 -0.0299266 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1298 1299 6.20567 -0.169428 -0.399089 -0.011463 0.11987 -0.0607119 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1249 1299 -0.113522 -2.91989 -0.256649 0.0538864 0.0122353 0.024665 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1299 1300 6.19215 -0.193602 -0.357342 0.0234807 0.113824 -0.00232494 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1250 1300 -0.0575381 -3.15703 -0.0173465 0.0560862 -0.0181203 -0.0417794 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1300 1301 6.22112 -0.0285158 -0.401262 -0.00606963 0.129094 -0.00593831 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1251 1301 -0.0208661 -3.04281 -0.262711 0.0486373 -0.0116369 -0.0227831 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1301 1302 6.34695 -0.123071 -0.457444 0.0048172 0.130174 -0.0904355 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1252 1302 -0.17397 -3.06393 -0.108863 0.0478713 -0.00453879 -0.0394134 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1302 1303 6.29111 -0.166395 -0.306891 -0.00519042 0.124023 0.0435879 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1253 1303 -0.0151913 -3.10748 -0.0844892 0.0603145 0.00180362 0.0129624 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1303 1304 6.31488 -0.202562 -0.344266 -0.00334094 0.135412 0.00399967 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1254 1304 0.0651676 -3.18321 -0.103595 0.0556416 -0.00419141 -0.00132177 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1304 1305 6.35699 -0.141824 -0.373519 0.00516648 0.133134 -0.0213091 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1255 1305 -0.0440867 -3.07231 -0.112743 0.0574387 -0.00359851 -0.0357969 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1305 1306 6.30369 -0.190767 -0.443207 -0.00739282 0.129526 -0.0846501 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1256 1306 -0.123172 -3.18236 -0.125023 0.0496843 0.0127799 0.000362878 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1306 1307 6.44043 -0.123385 -0.501931 -0.021574 0.123638 -0.0128373 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1257 1307 0.0905932 -3.08052 0.127835 0.0783303 -0.0063064 -0.0239268 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1307 1308 6.21538 -0.152431 -0.359177 -0.00578684 0.131289 -0.0588231 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1258 1308 -0.100321 -3.02651 -0.221678 0.0798382 -0.00937771 -0.00299728 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1308 1309 6.27574 -0.154201 -0.518586 -0.000907577 0.115278 0.00984685 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1259 1309 -0.0283104 -3.10143 -0.272325 0.0537936 -0.000298833 -0.0202115 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1309 1310 6.09744 -0.226017 -0.258046 -0.0115795 0.114699 -0.0443007 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1260 1310 -0.0214668 -3.03514 -0.187348 0.0631736 0.00419606 -0.0324818 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1310 1311 6.20693 -0.0159063 -0.19181 -0.00987638 0.128406 0.0356525 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1261 1311 0.0726882 -2.98127 -0.144517 0.0644936 -0.0196089 0.0325518 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1311 1312 6.29708 -0.158061 -0.146104 0.0108482 0.134657 0.0114973 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1262 1312 0.00471941 -3.09863 -0.116504 0.0665405 0.00399041 -0.0219051 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1312 1313 6.34431 -0.0177462 -0.298745 -0.00242028 0.120898 -0.0570523 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1263 1313 0.1264 -3.18058 0.071293 0.049349 -0.00179828 -0.0209318 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1313 1314 6.24302 -0.30347 -0.375339 -0.000830958 0.119596 -0.0236711 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1264 1314 -0.14519 -3.21131 -0.198725 0.0613887 0.000136054 0.0094161 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1314 1315 6.31953 -0.237597 -0.21995 0.00103115 0.125343 0.0467928 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1265 1315 0.0172603 -3.10497 -0.0672765 0.0614839 0.00463369 0.0103852 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1315 1316 6.11825 -0.118747 -0.465761 0.0074704 0.125082 0.0793701 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1266 1316 -0.042448 -3.00457 -0.150366 0.0518905 -0.0339651 0.0330414 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1316 1317 6.22251 -0.171544 -0.378444 -0.00556181 0.138316 -0.0597551 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1267 1317 -0.0418052 -2.99817 -0.208835 0.0337551 0.00835285 0.0358527 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1317 1318 6.21844 -0.0718262 -0.339217 -0.0019239 0.136535 -0.00214604 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1268 1318 -0.0760421 -2.87396 -0.0420749 0.0472971 0.00278051 0.0474409 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1318 1319 6.2523 -0.194656 -0.254226 0.00873374 0.12282 0.0680378 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1269 1319 0.101262 -2.84592 -0.213601 0.0616402 0.00595651 -0.0550343 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1319 1320 6.34696 -0.123717 -0.29561 -0.00765357 0.11189 -0.0212815 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1270 1320 0.0903656 -3.00274 -0.141047 0.076211 -0.00417802 -0.00582132 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1320 1321 6.16656 0.0333055 -0.377473 0.000487587 0.117168 -0.066752 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1271 1321 0.0231358 -2.84813 -0.0955439 0.0738655 0.0152974 0.0347263 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1321 1322 6.24314 -0.130521 -0.364895 0.00602578 0.103819 -0.00714588 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1272 1322 0.196866 -3.05021 0.025311 0.0654254 -0.00668304 0.0156272 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1322 1323 6.22752 -0.134193 -0.414806 -0.0171638 0.12082 -0.0376235 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1273 1323 -0.0727416 -3.1449 0.0670576 0.0595661 -0.0106434 -0.0281229 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1323 1324 6.2488 0.0423297 -0.47685 -0.00239673 0.114041 -0.0306187 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1274 1324 -0.0156132 -3.00505 -0.295934 0.0560122 -0.00522284 -0.0139018 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1324 1325 6.18545 -0.0947276 -0.346643 -0.00542558 0.138176 -0.0211824 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1275 1325 0.0789107 -3.12503 0.142463 0.0618578 -0.00282627 0.0312357 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1325 1326 6.23699 -0.298 -0.228957 -0.000149999 0.127537 0.000587954 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1276 1326 -0.0672725 -3.153 -0.0609681 0.081745 -0.00187555 0.0643672 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1326 1327 6.23197 -0.26787 -0.390065 0.00747707 0.132918 -0.0378892 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1277 1327 0.0913388 -2.99895 0.0160893 0.0842274 -0.00302083 -0.0315639 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1327 1328 6.18426 -0.144952 -0.475915 -0.00835148 0.117644 0.0148712 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1278 1328 0.0164034 -3.07669 0.0493066 0.0744174 -0.00921978 -0.0162468 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1328 1329 6.18676 0.0648548 -0.499528 0.00706569 0.135685 0.00277929 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1279 1329 -0.0222329 -3.02261 -0.065597 0.0592349 -0.00741687 0.0159005 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1329 1330 6.15092 -0.0838465 -0.440878 0.00438362 0.125174 0.0507155 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1280 1330 0.0725016 -2.98363 -0.136355 0.0744213 -0.00860575 -0.0185231 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1330 1331 6.23806 -0.221246 -0.303774 -0.00183151 0.129366 -0.00519121 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1281 1331 -0.0213452 -3.10214 -0.143385 0.0638852 0.00848861 0.0369964 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1331 1332 6.27513 -0.0853939 -0.411111 0.0102379 0.120619 -0.0400112 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1282 1332 0.0328465 -3.1208 -0.169905 0.0714499 -0.0108968 0.0770387 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1332 1333 6.2786 -0.223558 -0.195378 0.0113889 0.127027 0.0288591 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1283 1333 -0.0300653 -2.87785 -0.011728 0.0604565 -0.00457112 -0.0246904 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1333 1334 6.39039 -0.00275384 -0.533357 -0.0224172 0.135746 0.000182133 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1284 1334 -0.0541019 -3.16241 -0.0731676 0.0650972 -0.00280485 0.0482165 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1334 1335 6.20043 -0.159617 -0.424376 -0.0179198 0.111197 -0.0543473 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1285 1335 -0.123151 -3.11357 -0.0709806 0.0619399 -0.0219791 -0.00586649 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1335 1336 6.42572 -0.102746 -0.535746 0.00347688 0.12939 -0.0215104 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1286 1336 0.0846766 -3.13313 -0.172657 0.0711094 0.0130331 -0.0236692 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1336 1337 6.28704 -0.147034 -0.470362 0.000200042 0.116975 -0.054245 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1287 1337 0.129784 -3.08153 -0.191773 0.0515718 0.011975 -0.0732215 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1337 1338 6.30014 -0.112928 -0.302107 -0.00913041 0.142751 -0.0668146 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1288 1338 0.0912647 -3.04488 -0.0878891 0.0724135 -0.00214719 0.00114433 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1338 1339 6.11531 -0.33832 -0.345553 -0.00795829 0.117375 0.0403616 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1289 1339 0.0633721 -3.02641 -0.176723 0.0340894 0.0175776 0.00220281 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1339 1340 6.02633 -0.164862 -0.27763 -0.00694843 0.135948 0.0355381 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1290 1340 0.040094 -3.13084 0.0623061 0.0693734 0.00366114 0.00679749 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1340 1341 6.2373 -0.126054 -0.476603 -0.00324391 0.124117 -0.0669994 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1291 1341 0.117051 -2.93544 -0.200153 0.0772734 -0.000996978 0.00103887 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1341 1342 6.25852 -0.103477 -0.434705 -0.0183101 0.115919 0.0432434 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1292 1342 -0.0954122 -3.11456 -0.214924 0.0636121 0.0195949 -0.0467751 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1342 1343 6.34528 -0.0859691 -0.300043 -0.00707373 0.134346 0.0880443 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1293 1343 -0.107863 -3.0765 -0.138434 0.0731123 0.00188181 -0.0199851 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1343 1344 6.22885 -0.170272 -0.494296 -0.00801141 0.126607 0.0503689 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1294 1344 -0.0506967 -3.11434 -0.212269 0.0521337 0.0127944 -0.0175316 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1344 1345 6.15728 -0.0504386 -0.358963 -0.0128624 0.139655 -0.0272258 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1295 1345 0.100709 -3.21198 -0.24691 0.061676 -0.0052131 -0.0228803 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1345 1346 6.0505 -0.157932 -0.318045 -0.0159028 0.124094 -0.042166 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1296 1346 -0.0193429 -3.02744 -0.193487 0.0592263 -0.00759576 0.0674409 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1346 1347 6.47365 -0.000612863 -0.514904 0.00969294 0.129354 0.000967374 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1297 1347 0.0708384 -3.25031 -0.118709 0.0703136 0.0132948 0.0214276 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1347 1348 6.2339 -0.00389345 -0.419243 0.00766642 0.121445 -0.0516315 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1298 1348 0.00108843 -2.97985 -0.0529146 0.0541891 -0.00852176 0.0250052 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1348 1349 6.14442 -0.166148 -0.547432 -0.00168206 0.121439 -0.0274039 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1299 1349 -0.0774533 -2.99245 -0.102199 0.0672855 0.00690929 -0.0856849 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1349 1350 6.24987 0.0348018 -0.347181 0.0115012 0.124663 0.00274186 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1300 1350 -0.135449 -3.18796 -0.130342 0.0511162 -0.01106 0.0619865 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1350 1351 6.35901 -0.154356 -0.41679 0.0143761 0.110358 -0.00753472 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1301 1351 0.0863229 -3.01904 -0.146394 0.0551198 0.00785159 0.0996557 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1351 1352 6.34683 -0.147685 -0.477567 -0.0106044 0.125373 -0.0921588 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1302 1352 -0.0886227 -3.07618 0.0863092 0.061364 -0.000349922 -0.0135701 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1352 1353 6.17108 -0.117185 -0.379815 -0.00688363 0.148603 -0.0503782 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1303 1353 0.098698 -3.03124 -0.145067 0.0424208 -0.00513333 -0.087276 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1353 1354 6.19896 -0.153606 -0.36276 -0.000610075 0.135646 -0.0922879 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1304 1354 -0.192031 -3.13288 0.0865867 0.0588621 0.0154258 0.0409268 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1354 1355 6.21077 -0.109665 -0.333462 0.00383074 0.137909 0.0174263 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1305 1355 0.0730041 -3.23254 -0.0434189 0.0539883 -0.00292294 -0.000401201 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1355 1356 6.02145 0.0205289 -0.549595 -0.00213076 0.119904 0.0208861 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1306 1356 0.0144543 -3.20331 0.040632 0.0622832 0.0263164 -0.0335154 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1356 1357 6.19608 -0.175023 -0.492295 -0.00980655 0.13878 -0.0169445 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1307 1357 0.000991237 -3.19475 -0.233741 0.0553458 -0.000679122 -0.054863 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1357 1358 6.32081 -0.0949116 -0.47565 -0.00557439 0.137245 0.000416272 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1308 1358 -0.171001 -2.93116 -0.0731253 0.0516754 -0.0034792 0.0331167 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1358 1359 6.16269 0.02142 -0.447676 0.00340591 0.139982 -0.00580837 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1309 1359 0.0849326 -2.85309 -0.173527 0.0673889 -0.000299645 0.0139254 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1359 1360 6.17655 -0.0299125 -0.316326 -0.010134 0.135787 0.0453249 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1310 1360 0.0788349 -3.01811 -0.166758 0.0524034 0.0159887 -0.00251527 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1360 1361 6.30924 0.0763557 -0.559063 0.00275395 0.133246 -0.0498026 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1311 1361 -0.0457107 -2.97227 0.0170211 0.0646043 -0.000215917 -0.0336582 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1361 1362 6.18382 -0.127721 -0.356647 -0.00513167 0.130489 0.00630343 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1312 1362 0.0391832 -3.04532 -0.17623 0.072537 0.00707339 -0.0277942 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1362 1363 6.35586 -0.36993 -0.284798 -0.000716211 0.116358 -0.034882 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1313 1363 -0.0514189 -3.02893 -0.315396 0.0473976 -0.0164098 0.0214352 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1363 1364 6.17803 -0.186773 -0.527587 0.0160689 0.122344 -0.0441987 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1314 1364 -0.0323157 -3.05847 -0.0958673 0.0584865 0.0087537 0.00964478 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1364 1365 6.31881 -0.229596 -0.495082 -0.00220729 0.126938 -0.0144915 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1315 1365 0.125174 -3.0133 -0.0689619 0.0741111 -0.00659632 0.0371802 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1365 1366 6.31475 -0.197426 -0.278192 0.0026716 0.107188 0.00581629 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1316 1366 0.234237 -2.96419 -0.0508271 0.0752879 0.00918547 0.0873697 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1366 1367 6.16042 -0.221415 -0.379171 -0.00821592 0.122627 -0.0402313 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1317 1367 0.122871 -3.10854 -0.114482 0.0635472 0.00987242 0.0116272 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1367 1368 6.05653 -0.171271 -0.254775 -0.0196225 0.117745 0.0203381 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1318 1368 0.0196499 -2.99553 -0.0891939 0.0658658 -0.0100712 0.048836 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1368 1369 6.08874 0.0328503 -0.387274 -0.00634521 0.116876 -0.0593773 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1319 1369 0.0294847 -3.09914 0.0669154 0.0497298 0.00346906 -0.0287709 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1369 1370 6.11512 -0.0346746 -0.42042 0.00345043 0.107816 -0.0290675 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1320 1370 -0.0243636 -3.11324 0.000406849 0.0690978 -0.00127054 -0.0858427 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1370 1371 6.2184 -0.393157 -0.348097 0.0107075 0.12454 0.0721411 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1321 1371 -0.0885003 -3.08063 0.00394994 0.0593954 0.00151714 -0.025069 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1371 1372 6.05691 -0.26693 -0.55506 -0.00164788 0.129256 0.0204186 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1322 1372 -0.0644299 -3.1561 -0.1362 0.0779913 0.00945756 0.0624406 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1372 1373 6.10713 -0.124195 -0.254268 0.00953403 0.138629 -0.0250095 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1323 1373 -0.129697 -2.82568 -0.0770265 0.0863426 -0.00621421 -0.0595498 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1373 1374 6.23581 -0.26679 -0.548397 0.00987692 0.120844 0.0362534 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1324 1374 -0.031255 -2.96979 -0.0713494 0.0492207 -0.00675091 0.015638 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1374 1375 6.26018 -0.154932 -0.306531 0.00785009 0.141337 -0.00623773 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1325 1375 -0.00792822 -3.10115 -0.0591035 0.060535 0.000214208 0.0296064 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1375 1376 6.04549 -0.32269 -0.421921 -0.0147898 0.110048 -0.0580431 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1326 1376 -0.0375512 -3.03737 -0.126621 0.0768076 -0.00439573 0.110714 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1376 1377 5.9869 -0.226792 -0.364534 0.00448135 0.126773 -0.0780523 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1327 1377 0.123801 -3.1379 -0.177073 0.0588106 -0.00876132 -0.00179833 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1377 1378 6.24655 -0.0563683 -0.455999 0.000603677 0.135794 0.0145561 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1328 1378 0.0473298 -3.06573 -0.112554 0.0683254 0.00356538 -0.0043221 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1378 1379 6.14658 -0.296394 -0.269106 -0.00554602 0.120544 -0.0326916 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1329 1379 -0.0299222 -2.98244 -0.0324959 0.0462015 -0.00330524 -0.0466604 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1379 1380 6.17964 -0.369421 -0.379227 0.00334583 0.130517 -0.0687187 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1330 1380 0.0112869 -3.06834 0.0314856 0.0663052 0.00564651 -0.0511797 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1380 1381 6.24977 -0.0820678 -0.384023 -0.00556243 0.11058 0.00709975 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1331 1381 0.221602 -3.09163 0.0614727 0.061958 -0.000203844 0.0122524 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1381 1382 6.13005 -0.183719 -0.368163 0.0184854 0.126183 -0.0189129 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1332 1382 0.118677 -3.11276 -0.261401 0.0508654 -0.00583509 0.029423 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1382 1383 5.99288 -0.371239 -0.382527 0.00129876 0.125701 -0.0929394 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1333 1383 -0.0791063 -3.12113 0.163113 0.0472803 0.00913988 0.0121603 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1383 1384 6.35917 -0.13502 -0.395678 0.0153094 0.115308 -0.0125983 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1334 1384 0.0665855 -3.00528 0.0403633 0.0792484 -0.00818354 0.0135477 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1384 1385 6.20461 -0.00668903 -0.529339 0.00137144 0.12598 -0.00332228 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1335 1385 0.00731679 -3.01045 -0.0693185 0.0587577 0.00338095 0.0381203 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1385 1386 6.10261 0.0345962 -0.451116 0.00205541 0.140139 0.04557 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1336 1386 0.0707095 -2.9723 -0.0640878 0.0703759 -0.00959158 -0.0105589 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1386 1387 6.06628 -0.242093 -0.536489 0.014487 0.120288 -0.0306972 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1337 1387 0.24516 -3.05638 -0.17008 0.0651738 0.000413062 -0.00123889 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1387 1388 6.42854 -0.160517 -0.433313 0.000449497 0.115891 -0.0510779 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1338 1388 -0.133061 -3.07977 0.00842736 0.0776013 0.0047655 -0.0490726 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1388 1389 6.34016 -0.0943848 -0.271538 0.00134892 0.134419 -0.0174397 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1339 1389 0.0267053 -3.08914 -0.174307 0.0663553 0.0111123 -0.0038368 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1389 1390 6.16941 -0.0900359 -0.255688 -0.0128628 0.124586 -0.0765119 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1340 1390 -0.065725 -3.16306 -0.22173 0.0662765 0.00772302 -0.00937377 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1390 1391 6.04025 -0.24079 -0.238049 -0.0150281 0.130099 -0.0434135 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1341 1391 0.249362 -2.97866 -0.137487 0.0653987 0.00169749 -0.0652879 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1391 1392 6.3639 -0.199885 -0.159773 0.00104207 0.106717 0.0234947 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1342 1392 -0.0188619 -2.96372 0.0335782 0.0568973 -0.0111872 -0.0620218 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1392 1393 6.25003 -0.279508 -0.367931 0.000527776 0.134087 -0.0907225 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1343 1393 0.101523 -3.01196 -0.0992638 0.070162 -0.00366289 0.11143 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1393 1394 6.21748 -0.160159 -0.290193 -0.0107113 0.131245 -0.0100895 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1344 1394 -0.10246 -3.06114 0.0283579 0.0622374 0.0154011 -0.0467315 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1394 1395 6.082 -0.222128 -0.478707 0.00850339 0.123402 -0.0126787 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1345 1395 0.126295 -3.02449 -0.119801 0.0534102 0.00605503 -0.029815 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1395 1396 6.07123 0.103348 -0.331839 -0.0136554 0.131052 0.0381617 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1346 1396 -0.164039 -2.81797 -0.128848 0.0695433 0.00788694 0.0136664 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1396 1397 6.28588 -0.0463461 -0.361253 -0.00721689 0.139579 0.0254278 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1347 1397 0.0642075 -3.12925 -0.283189 0.061878 0.00765653 0.0137282 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1397 1398 6.20156 -0.118891 -0.409095 0.0130242 0.140423 -0.063099 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1348 1398 0.061399 -3.1661 -0.0734478 0.0647782 -0.00487747 0.0290046 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1398 1399 6.09568 -0.0658503 -0.291645 0.0165812 0.118282 -0.0427588 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1349 1399 -0.14636 -3.15239 0.0734351 0.0736348 -0.0114041 0.0580626 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1399 1400 6.18937 -0.180996 -0.413041 0.00710056 0.116709 -0.0377543 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1350 1400 -0.140195 -3.13059 -0.116467 0.0543153 0.0200771 0.00669299 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1400 1401 5.99165 -0.154059 -0.204484 0.00728459 0.128189 0.0376016 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1351 1401 -0.0616465 -3.15171 -0.0461224 0.0468709 0.00362259 -0.00601178 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1401 1402 6.05785 -0.0653862 -0.342765 0.0030223 0.0984601 -0.00987176 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1352 1402 -0.122224 -2.78434 -0.193178 0.0697432 0.00272268 0.0239871 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1402 1403 6.22215 -0.0829228 -0.464193 0.00927284 0.138555 -0.00214689 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1353 1403 -0.0961264 -3.04238 -0.248621 0.0666803 -0.00440849 0.011247 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1403 1404 6.21331 -0.153434 -0.400361 -0.00681653 0.123235 0.0100431 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1354 1404 0.123914 -3.06153 -0.259859 0.0615485 -0.0046311 -0.0308019 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1404 1405 6.19031 -0.0573191 -0.335526 0.00911303 0.12737 -0.0116962 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1355 1405 -0.0435789 -3.06667 -0.0159335 0.0561305 0.00179222 0.00831948 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1405 1406 6.18312 -0.0382142 -0.540216 0.00699367 0.114161 -0.0317702 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1356 1406 -0.0250662 -3.19135 -0.312431 0.0720535 0.00404941 -0.0245335 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1406 1407 6.1622 -0.126882 -0.267793 0.0117852 0.129465 -0.0458126 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1357 1407 -0.0337986 -3.29913 -0.120742 0.0554299 0.0146751 0.0113163 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1407 1408 6.23149 -0.207789 -0.468071 -0.00928667 0.124123 0.0284846 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1358 1408 0.188488 -2.96307 -0.215817 0.0562167 -0.00583458 -0.0131889 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1408 1409 6.11789 -0.103072 -0.356617 -0.00465357 0.141164 -0.0107242 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1359 1409 0.0588821 -3.08888 -0.10601 0.0701974 0.0162021 0.0270288 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1409 1410 6.15333 -0.0880778 -0.330333 -0.00546819 0.12523 -0.0751604 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1360 1410 -0.130273 -3.03285 0.0446737 0.066687 -0.00584246 -0.0612057 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1410 1411 6.08747 -0.230189 -0.459166 -0.00129684 0.108804 -0.0442114 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1361 1411 0.137714 -3.07736 -0.34693 0.0461578 0.0022198 0.0277717 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1411 1412 6.27994 -0.0944692 -0.251418 0.00906917 0.129936 -0.0578556 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1362 1412 0.0617815 -2.90856 -0.119507 0.0581285 0.0201209 -0.0254075 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1412 1413 6.2563 0.111186 -0.399352 0.00835982 0.124868 0.0171425 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1363 1413 0.000388562 -2.95835 -0.273994 0.0632606 -0.00498305 0.0186935 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1413 1414 6.26289 -0.139937 -0.51785 -0.0056831 0.122524 -0.0690066 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1364 1414 -0.117077 -2.94846 -0.154331 0.0745735 -0.0133048 -0.0440171 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1414 1415 6.1037 -0.174219 -0.370236 0.011975 0.124678 -0.0498704 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1365 1415 0.138866 -3.08177 -0.273103 0.0509035 -0.01264 -0.0666915 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1415 1416 6.19373 0.0312867 -0.412646 0.00398377 0.139164 -0.0293642 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1366 1416 0.0815604 -3.11526 -0.140667 0.0489597 -0.00509044 -0.0211174 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1416 1417 5.97719 -0.153279 -0.233219 -0.0266029 0.123761 -0.0579885 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1367 1417 0.0851823 -3.00174 0.105478 0.0516367 -0.0116361 -0.0171806 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1417 1418 6.17937 -0.126027 -0.400826 0.0119704 0.116487 -0.00362574 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1368 1418 -0.0444368 -2.90327 -0.185914 0.0662058 0.00839529 0.00342798 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1418 1419 6.25898 -0.0528018 -0.512342 -0.00113869 0.116178 -0.147921 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1369 1419 -0.0490994 -3.12999 -0.0129322 0.0509604 -0.00666623 -0.0175448 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1419 1420 6.24686 -0.0848768 -0.398167 -0.0111941 0.121146 -0.0131136 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1370 1420 -0.0343025 -3.09612 0.0298384 0.0547074 -0.0040033 -0.00721476 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1420 1421 6.23642 -0.183417 -0.306788 0.00133654 0.128281 -0.0295159 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1371 1421 0.118178 -2.93711 -0.0889908 0.0780479 0.00716225 -0.0574702 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1421 1422 6.18093 -0.156664 -0.43569 0.0200686 0.116158 0.000661378 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1372 1422 -0.0925934 -3.00313 -0.0839782 0.0649498 -0.00857933 -0.0125595 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1422 1423 6.09856 -0.200275 -0.510928 0.0115847 0.123101 -0.0174179 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1373 1423 0.0799127 -3.13026 0.053292 0.0370658 0.00441546 -0.013664 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1423 1424 6.23155 -0.180851 -0.404976 -0.0173255 0.134618 -0.0742817 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1374 1424 -0.066994 -3.00604 -0.0426163 0.0809034 -0.00168159 0.00295714 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1424 1425 5.95385 -0.118479 -0.515534 0.00954057 0.129722 -0.0337531 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1375 1425 0.313067 -2.91797 0.0345355 0.072359 -0.00700212 0.00256193 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1425 1426 6.05494 -0.247218 -0.467427 0.00351528 0.133058 -0.00117462 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1376 1426 -0.160073 -3.05797 0.0140968 0.0707071 -0.0102097 -0.0330448 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1426 1427 5.96243 -0.0742347 -0.202936 -0.00693743 0.129894 -0.0435058 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1377 1427 0.0114447 -3.10837 -0.150238 0.0688077 -0.00769804 0.0277486 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1427 1428 6.18918 -0.156636 -0.291154 -0.0051626 0.115819 -0.0811012 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1378 1428 0.166134 -2.88169 -0.0126063 0.056382 -0.00323255 0.0536752 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1428 1429 6.08753 -0.0190211 -0.445059 0.0242494 0.124441 -0.0571014 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1379 1429 0.0128448 -3.03928 -0.130835 0.0473485 0.0165995 0.0315705 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1429 1430 6.21752 -0.139977 -0.277539 -0.00261023 0.147573 0.0051677 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1380 1430 0.189056 -3.04874 0.102951 0.0559536 0.0131767 -0.0583113 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1430 1431 6.13333 -0.118259 -0.462708 0.0231094 0.123543 0.00836591 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1381 1431 0.00165198 -3.11531 -0.0230139 0.0670188 -0.000306608 -0.0105856 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1431 1432 5.99663 -0.257932 -0.197358 -0.0108571 0.128803 -0.113567 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1382 1432 -0.208759 -2.98 -0.159831 0.0401332 0.00813426 -0.047469 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1432 1433 6.08133 -0.245919 -0.464953 0.0164291 0.121864 -0.0601259 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1383 1433 -0.0998267 -3.0062 -0.11769 0.0606215 -0.00551111 -0.0298601 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1433 1434 6.34284 -0.111503 -0.364125 -0.00837969 0.114923 0.012549 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1384 1434 -0.0040618 -2.88701 -0.0346106 0.0551135 0.00923711 0.0205142 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1434 1435 6.15365 -0.187555 -0.408228 0.0124158 0.11455 -0.0638346 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1385 1435 -0.232551 -2.85677 -0.0106074 0.0747041 0.010108 -0.0460196 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1435 1436 6.08677 -0.305591 -0.329864 -0.018071 0.128791 -0.012451 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1386 1436 0.0412898 -3.05322 -0.00766552 0.0892667 0.00212398 -0.0217395 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1436 1437 6.17393 -0.182168 -0.220124 -0.0062963 0.117772 0.04488 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1387 1437 0.0945153 -3.01835 -0.0651342 0.0752168 -0.0208646 0.0118985 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1437 1438 6.2243 -0.278793 -0.226109 0.00839665 0.131108 0.035376 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1388 1438 0.00684625 -3.02375 -0.160322 0.0583357 0.00629984 -0.0207399 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1438 1439 6.19107 -0.06378 -0.45245 -0.00512761 0.127324 0.0387043 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1389 1439 0.0533143 -2.92101 0.0682153 0.0670475 -0.000818174 0.0345932 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1439 1440 5.91366 -0.116944 -0.321484 -0.00437871 0.119168 -0.130488 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1390 1440 -0.0677061 -3.04323 0.0948217 0.0744655 -0.00117337 0.083724 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1440 1441 6.18863 0.128748 -0.552268 0.0173837 0.107879 -0.0106567 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1391 1441 0.114623 -3.1265 -0.062847 0.0416787 -0.0100751 0.00106035 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1441 1442 6.12783 -0.221019 -0.244211 0.00740432 0.11358 0.0235426 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1392 1442 -0.0744187 -3.11913 -0.0777796 0.0851612 0.0125156 0.0130687 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1442 1443 6.12316 -0.171644 -0.254996 -0.00124564 0.13014 -0.0401135 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1393 1443 0.0170717 -3.23287 0.0958371 0.0580701 -0.00762169 -0.0408247 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1443 1444 6.20766 -0.160746 -0.462858 0.0063381 0.118146 0.0020909 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1394 1444 -0.0186652 -3.12685 -0.268548 0.0502591 -0.00725028 -0.0308373 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1444 1445 6.09538 -0.214699 -0.294306 -0.0122057 0.112418 -0.07329 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1395 1445 0.0617102 -3.20129 -0.315528 0.0684298 -0.0194598 0.0489742 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1445 1446 6.01016 -0.153446 -0.203129 0.0194585 0.124313 -0.0212877 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1396 1446 -0.0168841 -3.00355 -0.0743806 0.0772402 0.0289977 0.00812042 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1446 1447 6.19772 -0.13341 -0.367262 0.00516644 0.13159 -0.0196683 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1397 1447 -0.0445362 -3.00702 -0.0515179 0.054395 -0.00634871 -0.042434 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1447 1448 6.075 -0.202533 -0.273878 0.00677098 0.1229 0.035129 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1398 1448 -0.0715959 -3.16938 -0.215106 0.0566154 -0.0126726 0.0222052 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1448 1449 6.0769 -0.157555 -0.271993 -0.00246021 0.119149 0.0127071 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1399 1449 -0.117625 -3.25715 -0.0273246 0.0701064 0.0107712 -0.0481098 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1449 1450 6.04936 -0.152104 -0.334901 -0.0132461 0.124931 0.0312824 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1400 1450 -0.11432 -3.22112 -0.143187 0.0592906 -0.00302804 -0.0321466 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1450 1451 6.0736 -0.0261451 -0.419548 0.0169376 0.103912 -0.0543292 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1401 1451 0.0970733 -3.03483 -0.170898 0.0585997 0.014997 0.0333254 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1451 1452 6.12136 -0.140748 -0.39245 0.0170421 0.134432 0.0323519 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1402 1452 0.0695612 -3.06127 -0.00410004 0.0796017 0.0157045 -0.0234827 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1452 1453 6.07048 -0.0358362 -0.298025 0.000312056 0.147379 0.065019 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1403 1453 -0.0691311 -3.16751 -0.135613 0.0553644 0.00761282 -0.0964677 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1453 1454 6.03095 -0.341544 -0.236688 0.010251 0.125193 -0.0751816 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1404 1454 -0.0665629 -2.90613 -0.112797 0.0742713 -0.000766948 -0.0436524 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1454 1455 5.96737 -0.118697 -0.317615 0.00420679 0.105808 -0.0245612 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1405 1455 -0.145496 -3.14114 -0.037312 0.0506323 0.00293545 -0.0295816 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1455 1456 6.15516 -0.219293 -0.339482 -0.0118371 0.113477 -0.106373 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1406 1456 -0.0680009 -2.96203 -0.153302 0.0678903 0.0172271 -0.0165301 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1456 1457 6.28059 -0.178807 -0.39012 0.00677239 0.116284 -0.0367025 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1407 1457 -0.0451566 -3.15697 -0.0886921 0.0720196 -0.0142984 0.0286645 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1457 1458 6.05287 -0.118721 -0.385972 0.00857199 0.138324 -0.0389104 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1408 1458 -0.0171086 -3.13116 0.0238625 0.068981 -0.0105539 -0.00990347 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1458 1459 5.89172 -0.0725097 -0.296829 -0.00231725 0.13542 -0.0639112 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1409 1459 0.0447583 -2.92111 -0.177546 0.0726917 0.0105957 -0.0595585 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1459 1460 6.13755 -0.206726 -0.437175 -0.00356085 0.129794 0.0302953 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1410 1460 0.0488749 -3.11124 0.110536 0.0440881 -0.0205042 -0.080661 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1460 1461 6.05655 0.01612 -0.407569 0.00516603 0.125982 -0.000677473 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1411 1461 -0.000562506 -3.08526 -0.152169 0.0545927 0.0020852 0.0746242 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1461 1462 6.11832 -0.121048 -0.487158 0.003971 0.117025 0.0223662 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1412 1462 0.0858479 -3.06055 -0.0716978 0.0825499 -0.0156003 0.111653 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1462 1463 5.99079 -0.20462 -0.386277 -0.000912133 0.119886 0.0126024 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1413 1463 -0.0917391 -3.07495 -0.200095 0.0476129 -0.00544581 -0.039587 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1463 1464 6.06114 -0.159668 -0.488708 -0.0087628 0.112866 -0.0934021 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1414 1464 0.0346657 -2.9515 -0.0695061 0.0613631 -0.0110999 0.0390885 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1464 1465 6.05344 -0.152504 -0.467002 -0.0172332 0.111851 -0.0581871 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1415 1465 0.0982136 -2.79815 0.100074 0.0548338 0.00258702 -0.0182369 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1465 1466 5.79639 -0.250515 -0.353694 -0.000257374 0.105969 0.0292526 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1416 1466 0.00521197 -3.18371 -0.0845621 0.082391 -0.000314755 0.0378731 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1466 1467 6.05326 -0.360524 -0.38023 -0.0100579 0.120634 -0.0882227 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1417 1467 0.0820985 -3.02064 -0.134152 0.0780365 0.00589157 -0.0260725 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1467 1468 6.13361 -0.172173 -0.400285 0.00356977 0.140868 -0.0189514 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1418 1468 -0.0615935 -3.16019 -0.120833 0.0702464 0.005434 0.039276 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1468 1469 5.87955 -0.0870466 -0.320997 0.0102548 0.135626 -0.0976272 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1419 1469 -0.113872 -3.01411 -0.22652 0.0630839 0.00334795 0.0139758 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1469 1470 6.1625 -0.0770182 -0.261371 0.0115992 0.112337 -0.0134101 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1420 1470 0.128669 -3.06275 -0.116707 0.0687729 0.000531634 -0.0397298 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1470 1471 6.01587 -0.198168 -0.677768 -0.00707955 0.103314 0.0422 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1421 1471 -0.02931 -3.20346 -0.0236705 0.0584768 -0.017075 -0.0319344 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1471 1472 5.98135 0.0381998 -0.319193 0.00804527 0.130399 0.0224076 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1422 1472 -0.106077 -2.9925 -0.0624821 0.073748 0.00686503 0.0393698 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1472 1473 6.03524 -0.228531 -0.444687 -0.00750233 0.122549 -0.0665912 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1423 1473 -0.0239414 -3.02144 0.0058184 0.0708999 -0.00526973 0.0695402 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1473 1474 6.15876 -0.147951 -0.482231 -0.00944582 0.117945 -0.102802 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1424 1474 0.190346 -3.02244 -0.130642 0.0732372 -0.00116514 -0.0162531 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1474 1475 6.07276 -0.319651 -0.215809 -0.0122446 0.0995757 -0.00173406 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1425 1475 0.070112 -3.16877 -0.0659235 0.0486081 -0.00378028 -0.0771792 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1475 1476 6.19029 -0.0943584 -0.251671 0.0105876 0.107864 -0.0197862 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1426 1476 -0.00797889 -2.97364 0.0134975 0.05733 -0.00438671 0.0436236 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1476 1477 6.02899 -0.315797 -0.546651 0.0148656 0.118713 -0.0595451 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1427 1477 0.0392187 -2.95795 -0.0517485 0.0646616 0.0118014 -0.0199018 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1477 1478 5.99699 -0.308442 -0.256416 -0.00164928 0.119522 -0.0514924 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1428 1478 -0.0164042 -3.24258 0.202607 0.0650985 -0.0039974 0.0165545 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1478 1479 6.02757 0.0471519 -0.422199 0.00541481 0.141026 -0.0393898 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1429 1479 0.0770042 -3.15714 -0.134491 0.0764393 0.00660087 -0.0126845 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1479 1480 6.16629 -0.150351 -0.45152 0.00665076 0.121026 -0.0255925 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1430 1480 0.232111 -3.0744 -0.0264087 0.0549031 0.00160062 -0.0261133 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1480 1481 5.90642 -0.176904 -0.332377 0.00387056 0.123183 0.0176196 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1431 1481 -0.122164 -3.07109 -0.138505 0.0660462 0.00409373 -0.0388179 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1481 1482 5.98013 -0.288847 -0.35072 0.0202979 0.12584 0.050431 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1432 1482 -0.0694643 -3.14477 -0.0191628 0.0453165 -0.0110355 0.0212669 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1482 1483 5.89233 -0.1167 -0.176689 -0.00419559 0.110337 -0.0688524 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1433 1483 -0.163045 -3.05614 -0.126269 0.0662233 0.0112792 0.0583533 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1483 1484 6.07312 -0.130923 -0.344971 -8.07498e-05 0.131057 -0.0864181 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1434 1484 0.197643 -2.96686 0.0603323 0.0703616 -0.00650056 0.0386695 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1484 1485 6.16322 -0.190019 -0.280612 0.00212731 0.111561 -0.0901867 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1435 1485 0.0384799 -3.15804 -0.153314 0.07026 0.00964581 -0.00568065 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1485 1486 6.09943 -0.193193 -0.323324 0.00558652 0.120831 -0.0482617 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1436 1486 0.0415012 -3.10148 0.0240764 0.0788238 0.00923461 0.0129404 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1486 1487 6.00874 0.0768275 -0.41798 0.0166022 0.121765 -0.0206124 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1437 1487 0.108971 -3.07799 -0.110145 0.0736319 0.00148968 -0.020866 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1487 1488 5.63109 -0.160346 -0.225785 -0.00466224 0.110715 -0.049523 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1438 1488 -0.044113 -2.99646 -0.104815 0.0693849 0.00386431 0.0780909 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1488 1489 6.05897 0.057926 -0.316827 -0.0118161 0.120749 -0.00172968 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1439 1489 -0.149219 -3.24801 -0.0301921 0.0539367 -0.013061 -0.0237986 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1489 1490 6.16847 -0.309778 -0.2984 -0.0117436 0.131846 -0.0437028 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1440 1490 0.112179 -3.00944 -0.120006 0.0494516 -0.00881205 0.0137996 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1490 1491 6.09984 -0.120332 -0.37713 0.0113995 0.115744 0.00971879 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1441 1491 -0.00439428 -3.01418 -0.203456 0.0594241 -0.00702853 -0.0303928 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1491 1492 5.88367 -0.0629221 -0.209305 -0.0156856 0.127092 -0.0219118 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1442 1492 -0.109151 -3.22516 0.156737 0.0610014 0.00891273 0.0404915 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1492 1493 6.068 -0.230995 -0.281951 -0.0156341 0.116885 -0.0131461 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1443 1493 0.0220061 -3.01042 0.0186233 0.0546629 -0.0179082 0.0500645 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1493 1494 5.91328 -0.354315 -0.32983 0.0115276 0.104371 -0.123597 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1444 1494 -0.0226628 -2.97448 -0.257686 0.0658895 -0.00297107 0.0627458 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1494 1495 6.00362 -0.242939 -0.477028 0.00582819 0.118106 -0.0391929 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1445 1495 -0.0831201 -3.0404 -0.139814 0.0516752 -0.0233197 0.0277563 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1495 1496 6.05784 -0.119466 -0.520138 -0.00291896 0.122902 -0.103181 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1446 1496 0.144303 -2.95004 -0.104787 0.0653108 0.0020728 0.10304 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1496 1497 5.97743 -0.266069 -0.398548 0.00109539 0.107392 -0.0703816 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1447 1497 0.164602 -3.18762 -0.201016 0.0773302 -0.00152468 -0.00937868 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1497 1498 6.03483 -0.00999005 -0.424085 -0.00205763 0.112621 -0.0450435 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1448 1498 -0.0949916 -3.04431 0.0663403 0.0511379 -0.0152116 0.00495744 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1498 1499 5.94019 -0.291595 -0.392269 -0.0095386 0.107198 -0.0240439 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1449 1499 0.0579622 -3.126 0.048343 0.0736293 0.00454796 -0.0151949 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1499 1500 5.94704 -0.17863 -0.26738 -0.000850967 0.109864 -0.019029 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1450 1500 -0.0122964 -3.03331 -0.137219 0.0491206 0.00104854 0.0410658 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1500 1501 5.98286 -0.170064 -0.198508 -6.94832e-05 0.125728 -0.133179 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1451 1501 0.242926 -3.09036 0.0153387 0.0626338 -0.0118128 0.0308092 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1501 1502 5.99281 -0.117677 -0.118552 0.00406159 0.112915 0.011944 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1452 1502 0.0371973 -3.00307 0.0262124 0.06579 -0.00629308 -0.0133447 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1502 1503 6.16767 -0.179064 -0.349133 -0.0107951 0.140918 -0.0617012 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1453 1503 -0.0245438 -3.05885 -0.111534 0.0639343 -0.0161155 0.0118561 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1503 1504 5.95318 -0.172401 -0.427493 -0.00540398 0.132854 -0.0433293 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1454 1504 -0.166886 -3.13229 -0.0732931 0.0545925 0.00206823 -0.0476691 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1504 1505 5.8782 -0.172979 -0.431631 -0.0141913 0.114533 -0.0330959 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1455 1505 -0.163036 -3.03205 -0.00025729 0.0635217 0.00920785 -0.10096 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1505 1506 5.84763 -0.151272 -0.536484 0.0197927 0.128274 -0.0577312 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1456 1506 0.0771592 -3.10403 -0.138116 0.0718416 0.012668 0.0278719 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1506 1507 5.87092 -0.222001 -0.456434 -0.0065847 0.121136 -0.0234796 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1457 1507 0.0484934 -2.98207 -0.164762 0.0346717 -0.0094675 0.055489 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1507 1508 6.0398 -0.270812 -0.166162 0.00432724 0.108029 0.00101333 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1458 1508 0.0815976 -3.08308 -0.102886 0.0394647 0.00456846 -0.000392664 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1508 1509 5.91221 -0.289195 -0.412727 -0.00927877 0.120345 -0.101028 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1459 1509 0.156271 -2.99707 -0.191499 0.0681083 0.00963372 0.0253516 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1509 1510 5.85272 -0.37319 -0.561597 -0.00559181 0.135547 -0.0295506 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1460 1510 4.05521e-05 -3.04457 -0.124608 0.0764181 0.0148044 0.0312512 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1510 1511 5.78371 -0.198786 -0.348603 0.0168736 0.0928275 -0.00655454 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1461 1511 0.0331207 -3.09185 -0.137245 0.0683752 0.0095138 0.0144855 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1511 1512 5.92286 -0.194858 -0.0916729 0.00107064 0.122295 -0.0881439 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1462 1512 0.0908232 -3.0238 -0.101309 0.0711652 0.0140852 0.0114161 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1512 1513 6.01927 -0.042442 -0.385958 0.000583265 0.123155 0.00567899 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1463 1513 0.00864268 -3.04522 -0.123863 0.0821691 0.0182979 -0.0274555 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1513 1514 5.95877 -0.194465 -0.326077 0.00397247 0.106627 -0.0160681 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1464 1514 -0.0502985 -3.12814 -0.0510892 0.0576524 -0.00889767 0.0235024 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1514 1515 6.0762 -0.265267 -0.492219 -0.00104569 0.11212 -0.0107924 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1465 1515 -0.00707759 -3.03875 -0.0285588 0.0559109 -0.00778751 -0.0600034 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1515 1516 5.98213 -0.0818445 -0.240155 0.00718568 0.12 -0.0387357 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1466 1516 -0.208393 -3.0294 -0.0746222 0.0549912 0.00169751 -0.018117 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1516 1517 5.87105 -0.134005 -0.440708 0.0125851 0.10533 0.0157576 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1467 1517 -0.08451 -3.04205 -0.0603531 0.0604685 0.00515505 -0.0462448 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1517 1518 5.92085 -0.313127 -0.314374 -0.0077797 0.119137 -0.00294262 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1468 1518 -0.0505602 -2.99182 -0.0667217 0.0655882 -0.0104671 0.0445742 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1518 1519 6.00421 -0.112948 -0.446379 -0.00223438 0.133424 -0.00115862 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1469 1519 -0.173974 -2.87874 -0.24046 0.0466518 -0.002804 0.0405722 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1519 1520 5.95863 -0.122336 -0.385533 0.00491622 0.122611 -0.0362417 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1470 1520 0.0793507 -3.09859 0.0506259 0.0528458 -0.0210768 0.0272711 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1520 1521 5.82393 -0.191902 -0.301191 0.0039109 0.110866 -0.0731426 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1471 1521 -0.0849729 -3.13148 -0.0183556 0.0596168 -0.0102684 -0.043532 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1521 1522 5.7463 -0.29481 -0.337992 -0.00549352 0.117202 -0.032945 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1472 1522 0.0875691 -3.04439 -0.301831 0.0467093 0.00309956 -0.0660296 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1522 1523 6.06437 -0.251527 -0.25787 -0.00838409 0.119691 -0.0684587 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1473 1523 0.0440002 -2.88071 0.0616479 0.0633957 -0.0156538 0.00468792 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1523 1524 6.01187 -0.134671 -0.284085 -0.005816 0.108558 -0.0718074 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1474 1524 -0.0292739 -3.01869 -0.136298 0.0766686 -0.00995432 -0.0108085 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1524 1525 5.892 -0.179557 -0.515688 -0.00162244 0.121657 -0.0220181 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1475 1525 0.0348511 -3.03297 -0.307273 0.0605437 -0.00543309 -0.0323728 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1525 1526 5.8185 -0.133914 -0.141418 -0.00258167 0.113294 -0.0435976 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1476 1526 0.200722 -3.03673 -0.198971 0.0601141 -0.00171392 -0.00539927 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1526 1527 5.83975 -0.199714 -0.382486 -0.00418352 0.106711 -0.076774 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1477 1527 0.0704842 -3.01271 -0.103731 0.0646671 -0.0008368 0.00136598 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1527 1528 5.91736 -0.241596 -0.420749 -0.00344651 0.122921 -0.0654129 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1478 1528 -0.26117 -3.01328 -0.100638 0.0591198 0.00429147 0.0284717 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1528 1529 5.79337 -0.134957 -0.550117 0.00056868 0.117669 -0.0428818 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1479 1529 -0.0738299 -2.8944 -0.0195218 0.0429103 0.00606049 0.00498765 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1529 1530 5.88823 -0.103277 -0.346065 -0.00219001 0.0997805 -0.00962669 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1480 1530 -0.0702237 -3.33992 -0.048626 0.0580585 -0.0146464 -0.0148905 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1530 1531 5.91472 -0.187818 -0.375774 0.00405881 0.133378 -0.000635866 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1481 1531 0.0471118 -2.96882 -0.0471514 0.0730989 -0.000801137 -0.0309024 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1531 1532 5.88493 -0.211666 -0.523099 -0.00260497 0.103609 -0.0298985 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1482 1532 0.132377 -2.97142 -0.0937641 0.0604169 0.0152166 0.0322203 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1532 1533 5.82982 -0.380093 -0.476638 0.00317657 0.114172 -0.0124295 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1483 1533 0.0480049 -3.01471 0.0816344 0.0528384 0.00715055 -0.00156575 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1533 1534 5.92871 -0.209305 -0.399149 -0.00743937 0.0971285 -0.0465478 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1484 1534 0.093426 -3.06443 -0.0992595 0.0538423 -0.0162916 -0.0266222 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1534 1535 5.95962 -0.300768 -0.382427 -0.00415626 0.0987859 -0.119812 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1485 1535 -0.0459628 -3.07576 -0.232439 0.0660294 -0.000407574 -0.00648659 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1535 1536 5.83785 -0.119313 -0.301585 0.00131275 0.119057 -0.0905173 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1486 1536 -0.142974 -3.23039 -0.112534 0.0634954 -0.0135311 0.0322473 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1536 1537 5.95114 -0.25736 -0.281579 -0.00706972 0.12354 -0.0776269 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1487 1537 0.0274043 -2.9532 -0.231942 0.0704048 -0.00614341 0.0582442 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1537 1538 5.87094 -0.3729 -0.208277 -0.0227541 0.137067 -0.0280577 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1488 1538 0.0370613 -2.91405 -0.0548517 0.0722532 0.00714865 0.0172267 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1538 1539 5.84388 -0.150725 -0.349349 0.00801198 0.118224 -0.099876 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1489 1539 -0.213618 -3.31568 -0.177221 0.0639273 0.00482042 -0.00063798 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1539 1540 5.81634 -0.135421 -0.555087 -0.0019541 0.11382 -0.0187826 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1490 1540 -0.241457 -3.04921 -0.0988095 0.0690001 0.000701801 0.00504568 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1540 1541 5.63269 -0.238251 -0.330804 0.0172518 0.106777 0.0221156 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1491 1541 0.095635 -3.09193 -0.0365968 0.0554264 -0.00559803 -0.0336795 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1541 1542 5.72755 -0.120957 -0.372014 0.00770878 0.11409 -0.0410835 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1492 1542 0.0129842 -2.97485 -0.0496116 0.0749496 0.0235896 -0.0220508 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1542 1543 5.99108 0.0197304 -0.265671 -0.000767736 0.128761 -0.0777125 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1493 1543 0.0162058 -3.13924 -0.0190449 0.0606079 0.00816592 -0.015555 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1543 1544 6.19967 -0.0738819 -0.254256 -0.00514373 0.0894225 -0.0341511 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1494 1544 -0.177366 -3.04872 -0.0104906 0.0844797 -0.0104946 0.0116971 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1544 1545 5.80372 -0.190032 -0.208933 0.011792 0.111487 -0.0834589 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1495 1545 -0.0858572 -2.92129 -0.297449 0.0666936 -0.0156252 0.0074547 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1545 1546 5.90347 -0.220884 -0.140256 -0.0100549 0.132204 -0.0889557 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1496 1546 0.0849363 -3.10063 -0.118535 0.0541621 0.0220473 0.0796636 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1546 1547 5.67361 -0.293754 -0.41847 -0.00810889 0.113289 -0.00374694 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1497 1547 0.00887894 -2.96862 -0.172428 0.0553777 -0.00966336 0.0275099 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1547 1548 5.81023 -0.230911 -0.205293 -0.00705718 0.121855 0.000586998 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1498 1548 -0.0369421 -3.09309 -0.0425388 0.0604782 -0.002838 -0.00450717 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1548 1549 5.91899 -0.330966 -0.474763 0.0150607 0.114179 -0.023839 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1499 1549 0.0949579 -3.08466 -0.209415 0.0614496 -0.0115627 0.00503602 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1549 1550 5.84152 -0.0485259 -0.3017 -0.0117662 0.123042 0.0554946 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1500 1550 0.00156628 -3.06113 -0.0297818 0.0620316 -0.0147953 0.0198973 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1550 1551 6.0009 -0.22941 -0.520813 0.00754493 0.121408 -0.100827 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1501 1551 0.0950155 -3.05002 -0.132304 0.0674602 -0.00983489 0.0192621 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1551 1552 5.80783 -0.32215 -0.434128 -2.80624e-05 0.117024 -0.035786 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1502 1552 0.0328266 -3.09963 -0.141513 0.0499989 -0.00280149 -0.0512595 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1552 1553 5.6913 -0.441063 -0.306862 -0.00802477 0.113641 -0.102734 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1503 1553 0.140479 -3.04174 -0.105443 0.0728809 0.00146524 -0.00099028 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1553 1554 5.78404 -0.338284 -0.317967 -0.0142854 0.11694 -0.0404216 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1504 1554 -0.112078 -3.14015 -0.21846 0.0615923 0.00208856 -0.0240485 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1554 1555 5.8828 -0.302725 -0.486025 -0.00174132 0.105688 -0.0931471 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1505 1555 0.0407665 -2.93725 -0.290733 0.0665326 -0.00933265 0.0132741 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1555 1556 5.8463 -0.146008 -0.253573 0.00686353 0.113494 -0.0883384 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1506 1556 0.183703 -2.96895 -0.050741 0.0669844 -0.00142952 -0.075122 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1556 1557 5.88169 -0.0990942 -0.408735 0.00277847 0.122369 -0.0335445 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1507 1557 0.245295 -3.00013 -0.270078 0.0592498 -0.00141938 -0.0447121 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1557 1558 5.82589 -0.166206 -0.358672 -0.00681034 0.109887 -0.034767 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1508 1558 -0.0636927 -2.97486 -0.216055 0.0411978 0.00108876 -0.00738468 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1558 1559 5.95843 -0.127235 -0.44534 -0.0048509 0.116929 -0.0735231 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1509 1559 0.158999 -3.20143 -0.166864 0.0656541 0.0117994 -0.0127503 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1559 1560 5.6615 -0.215944 -0.416092 -0.00199412 0.114097 -0.037835 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1510 1560 -0.0322777 -3.15676 -0.114948 0.0635113 -0.000208495 -0.0261909 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1560 1561 5.76049 -0.29065 -0.573953 0.00210919 0.107692 -0.0737341 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1511 1561 0.321175 -3.04157 -0.108344 0.0582586 0.00382299 0.0219256 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1561 1562 5.81755 -0.0890094 -0.54307 0.00565565 0.111724 0.01841 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1512 1562 0.0674057 -3.10072 -0.0309059 0.0514909 -0.0179714 0.01344 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1562 1563 5.69892 -0.190968 -0.264943 0.0151608 0.115723 -0.0573675 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1513 1563 -0.0832783 -3.01555 -0.0727245 0.0613226 -0.00813247 -0.0453113 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1563 1564 6.12145 -0.215822 -0.489462 -0.00497218 0.103094 -0.0188962 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1514 1564 0.00619854 -3.11583 0.00291023 0.068031 -0.0160581 0.00228582 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1564 1565 5.92713 -0.250536 -0.332552 0.0109503 0.117666 -0.0521221 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1515 1565 0.158505 -3.06267 0.0192168 0.0524892 0.0105107 -0.033417 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1565 1566 5.83814 -0.173257 -0.327372 -0.0166671 0.107469 -0.0955429 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1516 1566 0.0508353 -3.05966 -0.196511 0.0923874 0.000389881 -0.0254827 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1566 1567 5.66148 -0.192818 -0.217624 -0.00723749 0.113304 -0.0360662 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1517 1567 0.0834154 -3.07007 -0.131744 0.0650538 -0.000608748 0.0415096 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1567 1568 5.82959 -0.212556 -0.381363 0.000963062 0.122671 -0.0292327 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1518 1568 0.047666 -3.10564 -0.0815679 0.0587136 -0.00366369 -0.0206969 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1568 1569 5.81956 -0.211381 -0.352314 -0.00686106 0.103008 -0.11257 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1519 1569 0.0416736 -3.09731 -0.264139 0.0585296 0.0160115 0.0477856 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1569 1570 5.83564 -0.356768 -0.558223 -0.0133237 0.126058 -0.0423006 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1520 1570 0.139476 -2.90002 -0.134585 0.0659699 0.00290329 0.0196701 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1570 1571 5.83171 -0.181027 -0.400486 0.00524636 0.106886 -0.0737646 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1521 1571 0.0682854 -2.98598 -0.353151 0.0732769 0.0222844 -0.0125969 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1571 1572 5.85581 -0.165517 -0.537131 -0.0243718 0.111708 -0.0744955 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1522 1572 -0.01798 -2.99719 -0.204302 0.0644995 -0.00367124 -0.0670055 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1572 1573 5.90662 -0.094729 -0.291514 0.00198291 0.122052 -0.0644589 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1523 1573 -0.0701957 -3.22193 -0.0141426 0.0539316 0.00242078 0.00537524 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1573 1574 5.90962 -0.35592 -0.277949 0.00248369 0.113239 -0.0925231 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1524 1574 0.0515603 -3.02432 -0.246666 0.0580984 0.00999748 -0.142128 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1574 1575 5.69246 -0.441492 -0.428471 -0.00504572 0.129279 -0.0408155 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1525 1575 -0.0498292 -3.0713 -0.0289877 0.0630137 -0.00119014 -0.0407786 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1575 1576 5.71801 -0.351783 -0.346667 0.00979633 0.115284 0.00246374 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1526 1576 0.148204 -3.11252 -0.122259 0.0555761 -0.0036703 0.0288339 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1576 1577 5.77244 -0.230265 -0.342915 -0.00328031 0.115025 -0.0436336 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1527 1577 0.057824 -3.09071 -0.085049 0.0401411 0.00913436 -0.0359974 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1577 1578 5.96243 -0.147179 -0.37116 -0.0039555 0.132521 -0.0497224 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1528 1578 0.0276849 -2.89431 -0.0889154 0.0509554 0.00952733 -0.0592883 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1578 1579 5.68104 -0.261293 -0.391156 -0.00653185 0.112687 -0.0203868 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1529 1579 0.0257364 -3.1602 0.056284 0.0510245 -0.000781618 0.0533957 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1579 1580 5.68544 -0.0248533 -0.444981 -0.00369766 0.105983 -0.0652649 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1530 1580 0.205012 -3.06721 -0.103237 0.0678933 0.020496 -0.00761364 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1580 1581 5.93609 -0.169332 -0.181955 0.0138779 0.121232 -0.0289522 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1531 1581 -0.0751571 -3.10181 -0.069928 0.0572417 -0.0120146 0.0440557 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1581 1582 5.54992 -0.152544 -0.285497 0.00375113 0.120941 -0.0198732 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1532 1582 0.180332 -3.17757 -0.192242 0.0425063 0.00492029 -0.0480547 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1582 1583 5.67688 -0.139629 -0.367766 -0.00637417 0.113013 -0.0728457 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1533 1583 -0.178464 -2.93268 -0.171116 0.0673504 -0.0036134 0.0621937 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1583 1584 5.8078 -0.332436 -0.396811 0.00112272 0.100021 -0.0384031 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1534 1584 -0.0968383 -3.09195 -0.222963 0.0571767 -0.000397247 0.0170741 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1584 1585 5.77208 -0.121083 -0.305198 -0.00813589 0.109799 -0.0915337 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1535 1585 -0.0803853 -3.0655 -0.10692 0.0444203 0.00743466 -0.0400119 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1585 1586 5.70439 -0.0246809 -0.428153 -0.00870984 0.125529 -0.0734912 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1536 1586 -0.124951 -3.0527 -0.0749644 0.0431358 0.0137238 -0.0515109 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1586 1587 5.94212 -0.104465 -0.20606 -0.0121571 0.12349 -0.0543809 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1537 1587 0.0843247 -2.93162 -0.0166234 0.0579608 -0.011171 -0.0231839 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1587 1588 5.83269 -0.284165 -0.494471 0.00848985 0.103436 -0.10382 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1538 1588 -0.0354141 -3.07986 -0.0371913 0.067683 -0.00406239 0.0530327 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1588 1589 5.70446 -0.2841 -0.283626 0.00537396 0.119674 -0.0595997 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1539 1589 0.0579006 -3.12999 -0.115683 0.0565248 0.0162626 0.02948 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1589 1590 5.68211 -0.25275 -0.158042 0.00202559 0.122263 -0.0450793 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1540 1590 0.0309525 -3.05556 -0.144786 0.0561867 0.00374344 -0.0566783 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1590 1591 5.3438 -0.36873 -0.190521 0.00091118 0.116146 -0.0852498 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1541 1591 -0.0824848 -3.09321 -0.136869 0.0649271 0.000256575 -0.00962566 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1591 1592 5.78099 -0.294512 -0.425263 -0.00476385 0.11194 -0.0789823 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1542 1592 0.102397 -3.25193 -0.0840623 0.0556791 0.00840076 0.0750726 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1592 1593 5.57376 -0.201251 -0.444932 -0.00649834 0.12421 -0.0145933 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1543 1593 0.136431 -3.12683 -0.0761961 0.0501069 -0.000811528 -0.105396 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1593 1594 5.71974 -0.20467 -0.283885 -0.00187895 0.141016 -0.0746923 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1544 1594 -0.013614 -3.04535 -0.184227 0.0533517 -0.000210912 -0.0747208 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1594 1595 5.75849 -0.20117 -0.357509 -0.0302811 0.112856 -0.0221186 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1545 1595 0.00857537 -3.14204 -0.0663572 0.059851 0.0179518 0.0270832 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1595 1596 5.61286 -0.0884936 -0.31422 -0.0126588 0.126457 -0.131374 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1546 1596 0.152529 -2.94189 -0.138613 0.0683508 -0.0138919 -0.0557097 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1596 1597 5.77492 -0.109292 -0.125878 -0.0171986 0.0984815 -0.064501 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1547 1597 0.108353 -2.91482 -0.197133 0.0506047 0.00849604 -0.000736901 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1597 1598 5.66117 -0.061563 -0.391314 0.00736351 0.1182 -0.0754743 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1548 1598 -0.152337 -3.12747 -0.173032 0.0626554 -0.0187039 0.00766624 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1598 1599 5.70526 -0.276877 -0.441099 -0.0143323 0.117723 -0.0839891 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1549 1599 0.000407988 -3.12924 -0.276538 0.0588762 -0.000432243 -0.04753 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1599 1600 5.60682 -0.120076 -0.330928 0.00628235 0.123539 -0.0347865 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1550 1600 0.297469 -3.02632 -0.0428668 0.0787283 0.0125591 0.0137679 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1600 1601 5.64771 -0.279165 -0.443105 -0.00477294 0.11298 -0.0259905 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1551 1601 -0.12387 -3.21715 -0.148698 0.0532849 0.00251894 -0.0117197 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1601 1602 5.81012 -0.109233 -0.309062 0.00474167 0.099196 -0.136739 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1552 1602 -0.155186 -2.95413 -0.126659 0.0566545 -0.0192055 -0.022744 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1602 1603 5.70761 -0.264572 -0.515114 -0.00111677 0.111565 -0.0736347 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1553 1603 0.0382022 -3.02486 -0.0846732 0.0532651 -0.00646327 -0.0020424 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1603 1604 5.56281 -0.154022 -0.286283 0.000386446 0.124304 -0.0430972 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1554 1604 0.0467163 -3.06866 -0.148987 0.0789478 -0.000201119 0.0389988 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1604 1605 5.61783 -0.0363336 -0.268403 0.00221464 0.110349 -0.0525786 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1555 1605 0.0791336 -3.02089 -0.121887 0.0555259 -0.00910509 -0.0231167 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1605 1606 5.74654 -0.18503 -0.349848 0.00378276 0.11035 -0.069462 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1556 1606 -0.142713 -2.99072 -0.305487 0.0679541 -0.00634749 0.041413 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1606 1607 5.76855 -0.165762 -0.152218 0.018543 0.115527 -0.0785103 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1557 1607 0.150274 -3.20286 0.00644862 0.0586103 -0.00855788 0.0164565 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1607 1608 5.63459 -0.338279 -0.284295 0.0188354 0.110066 -0.0604448 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1558 1608 -0.0379044 -2.85366 -0.0437557 0.0717006 -0.0167016 -0.0155869 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1608 1609 5.73145 -0.0978749 -0.280522 -0.0114913 0.124443 -0.049845 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1559 1609 -0.194397 -2.9518 -0.0592383 0.0518265 0.0133258 0.00922732 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1609 1610 5.67285 -0.333748 -0.336244 0.00411706 0.103602 -0.116392 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1560 1610 -0.00375714 -3.02137 -0.0404717 0.0554744 0.0136632 0.0183815 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1610 1611 5.53061 -0.231102 -0.283425 0.000615865 0.102973 0.0505642 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1561 1611 -0.0358943 -3.12345 -0.00474627 0.0651309 0.0142175 0.0557261 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1611 1612 5.5764 0.00283082 -0.230684 0.000994843 0.114451 -0.0761232 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1562 1612 0.0659228 -2.9928 -0.159089 0.0719509 -0.00304922 0.0385667 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1612 1613 5.64868 -0.286334 -0.280741 0.0111761 0.131229 -0.0608806 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1563 1613 -0.17369 -3.1001 -0.264821 0.050077 0.00404418 -0.0130707 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1613 1614 5.74863 -0.217187 -0.232726 -0.000743087 0.11437 -0.07996 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1564 1614 -0.0166508 -3.03011 -0.208047 0.0514598 -0.00331119 -0.0449084 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1614 1615 5.68037 -0.233575 -0.373229 0.00474925 0.112884 -0.0193557 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1565 1615 -0.0967041 -2.97105 -0.11496 0.0519639 -0.00813856 0.0392753 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1615 1616 5.78489 -0.209503 -0.292304 0.002241 0.116515 -0.0234287 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1566 1616 0.0338935 -3.19303 -0.157456 0.058711 0.00313376 0.0199009 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1616 1617 5.60224 -0.178294 -0.329285 -0.00680134 0.124124 -0.0586121 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1567 1617 -0.0162452 -3.15712 -0.279401 0.0719426 -0.00345568 0.0368333 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1617 1618 5.4853 -0.336129 -0.462814 -0.0134851 0.109028 -0.0376728 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1568 1618 -0.102844 -3.14731 -0.178781 0.0645585 0.000934957 0.0206786 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1618 1619 5.65201 -0.208786 -0.318516 -0.000954612 0.113561 0.00449782 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1569 1619 0.0477148 -2.95365 -0.161581 0.0577269 -0.00294064 -0.0469588 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1619 1620 5.71771 -0.319449 -0.41066 0.00201193 0.111473 -0.0832197 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1570 1620 0.183173 -2.89732 -0.145997 0.080819 0.00356566 0.0232357 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1620 1621 5.54848 -0.282517 -0.358541 0.0170185 0.0982016 -0.104919 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1571 1621 0.137378 -3.17708 -0.200221 0.0498387 -0.0114542 -0.00189167 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1621 1622 5.53183 0.00483989 -0.35496 -0.00987197 0.11396 -0.0848484 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1572 1622 0.0461384 -2.98229 -0.0882955 0.0510345 -0.00211882 -0.0619753 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1622 1623 5.53053 -0.383895 -0.163466 -0.00454234 0.118862 -0.122108 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1573 1623 0.0796928 -3.21416 -0.0475025 0.0740122 -7.75462e-05 -0.0565686 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1623 1624 5.67842 -0.409818 -0.337252 -0.00709902 0.117899 -0.0734284 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1574 1624 0.222315 -3.06482 0.0530381 0.0611135 -0.00808136 -0.0360804 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1624 1625 5.75103 -0.248264 -0.4541 0.0126868 0.0978992 -0.00373233 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1575 1625 -0.108282 -3.08746 -0.165596 0.0592756 0.0058499 -0.0261984 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1625 1626 5.66925 -0.191549 -0.565643 0.0048126 0.110398 -0.134443 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1576 1626 0.105345 -3.16815 0.0341791 0.0534489 0.00102422 -0.0270134 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1626 1627 5.41653 -0.29655 -0.217024 -0.0152272 0.121261 -0.0877128 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1577 1627 0.00948316 -3.042 -0.148562 0.0789286 0.00402783 -0.00863581 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1627 1628 5.49879 -0.207547 -0.490245 -0.00604702 0.114273 -0.124554 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1578 1628 -0.0972393 -3.00185 -0.170597 0.0736478 -0.00536017 0.0557376 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1628 1629 5.36114 -0.0963816 -0.370428 0.00422355 0.11396 -0.142146 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1579 1629 0.0342073 -2.9237 -0.121685 0.0627764 -0.00522617 -0.0503367 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1629 1630 5.69037 -0.251802 -0.157803 -0.00074647 0.114668 -0.0777519 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1580 1630 0.138625 -2.80367 -0.0962346 0.0688963 0.0209701 0.0596788 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1630 1631 5.49614 -0.285244 -0.193573 -0.0175016 0.10328 -0.0562671 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1581 1631 -0.133626 -2.93352 -0.0487959 0.0612235 -0.00694272 -0.0184481 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1631 1632 5.61857 -0.180084 -0.260074 0.00309239 0.112297 -0.0385516 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1582 1632 0.00200666 -3.12127 -0.0231594 0.0629602 0.00956999 -0.00110633 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1632 1633 5.61879 -0.227054 -0.202296 -0.00120255 0.0889981 -0.0333077 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1583 1633 0.0254032 -3.03705 -0.191644 0.0691058 -0.0106546 0.0044343 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1633 1634 5.44046 -0.08572 -0.407531 0.0039125 0.108116 -0.0925526 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1584 1634 -0.0988332 -3.11012 0.0885873 0.081753 0.0098446 -0.0196322 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1634 1635 5.54424 -0.153366 -0.262257 0.0039212 0.12979 -0.00709443 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1585 1635 -0.03036 -3.16518 -0.276968 0.064361 -0.0111223 -0.0921271 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1635 1636 5.6326 -0.388838 -0.346591 -0.0111498 0.120114 -0.00586186 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1586 1636 0.00720786 -3.09961 -0.0169409 0.0650693 0.0104528 0.0500851 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1636 1637 5.4785 -0.312539 -0.203813 0.00497026 0.103047 -0.0380676 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1587 1637 0.0104427 -3.20077 -0.143173 0.0664791 0.00280422 0.0466656 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1637 1638 5.66111 -0.239979 -0.290939 -0.000742511 0.122235 -0.121049 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1588 1638 -0.02948 -2.82963 -0.0371475 0.0492193 0.00582857 0.0596119 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1638 1639 5.41803 -0.0392968 -0.216189 -0.00793861 0.114143 -0.0354136 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1589 1639 0.0658815 -3.01629 -0.155712 0.0433198 -0.00759661 0.00226155 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1639 1640 5.62971 -0.214313 -0.276993 0.00601698 0.102605 -0.0635528 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1590 1640 0.181601 -3.23754 -0.0428018 0.0677251 -0.00278767 -0.0261613 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1640 1641 5.75768 -0.199339 -0.281215 0.00940911 0.109109 -0.0396471 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1591 1641 0.076053 -3.28055 -0.0558072 0.0614747 -0.0157336 -0.0197351 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1641 1642 5.43598 -0.212853 -0.23949 0.00369504 0.108067 -0.0696886 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1592 1642 -0.152447 -3.21976 -0.0570661 0.0626118 -0.00128048 -0.0754866 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1642 1643 5.42725 -0.261564 -0.571297 -0.00760412 0.11099 -0.119274 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1593 1643 0.0409769 -3.00659 -0.205898 0.0515276 0.00408202 -0.0310424 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1643 1644 5.42862 -0.13988 -0.44302 -0.00219361 0.11347 -0.0621839 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1594 1644 -0.153103 -2.8164 0.0547661 0.0784733 0.0144601 -0.0278942 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1644 1645 5.64125 -0.18543 -0.207965 -0.00590996 0.102062 -0.0869638 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1595 1645 -0.00201381 -3.14387 -0.0924819 0.0571935 0.000944579 -0.0415041 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1645 1646 5.53901 -0.299434 -0.38595 0.0116954 0.108341 0.0209867 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1596 1646 -0.038192 -3.05168 -0.0614017 0.0524556 -0.0061408 0.0432445 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1646 1647 5.46448 -0.124707 -0.180061 -0.0131195 0.116975 -0.0928159 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1597 1647 0.126749 -3.1517 0.0630315 0.0701366 0.00112528 0.00316337 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1647 1648 5.63194 -0.0755708 -0.368714 0.00341192 0.107138 -0.0587038 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1598 1648 -0.0975346 -2.98387 -0.0200672 0.0753017 -0.00285773 -0.0201186 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1648 1649 5.52432 -0.24094 -0.26555 0.008667 0.116997 -0.0487044 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1599 1649 0.0902319 -3.21333 -0.176788 0.0612723 -0.00831218 -0.0744219 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1649 1650 5.54032 -0.285128 -0.341258 -0.0136427 0.123151 -0.0722945 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1600 1650 0.0113906 -2.93396 -0.0407956 0.0563525 0.0107655 -0.00287557 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1650 1651 5.52155 -0.207308 -0.122315 -0.00653354 0.124109 -0.0926272 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1601 1651 -0.0993613 -2.90503 -0.0932279 0.0495431 -0.00706941 0.0223639 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1651 1652 5.27444 -0.236102 -0.404528 -0.00798657 0.113578 -0.038441 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1602 1652 0.0681438 -3.04095 -0.297807 0.0526162 0.00716833 0.0222933 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1652 1653 5.51253 -0.220782 -0.167644 -0.0157178 0.0954799 -0.0720011 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1603 1653 -0.0878251 -3.15728 -0.148614 0.0758602 0.00323297 0.0177011 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1653 1654 5.38209 -0.314531 -0.468195 0.00968066 0.108625 -0.0828892 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1604 1654 0.0712583 -3.05481 -0.235197 0.0515433 -0.0069804 -0.043173 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1654 1655 5.53469 -0.158532 -0.279071 0.0108189 0.112169 -0.0741669 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1605 1655 -0.0625302 -2.9818 -0.0786953 0.0714198 0.00366227 -0.067973 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1655 1656 5.47425 -0.182735 -0.315019 -0.0133892 0.109108 -0.0818932 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1606 1656 0.0938803 -3.08946 -0.413693 0.0418843 -0.00223879 -0.0294188 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1656 1657 5.55803 -0.23683 -0.218304 -0.00923203 0.132747 0.0104853 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1607 1657 0.0369366 -3.05858 -0.198546 0.0577019 -0.010494 0.0829879 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1657 1658 5.54262 -0.238804 -0.360897 0.00975698 0.103127 -0.0703173 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1608 1658 0.00161531 -3.15978 -0.0607119 0.0664338 -0.00553071 0.0184819 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1658 1659 5.56632 -0.158518 -0.286174 -0.0120564 0.118405 -0.0629932 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1609 1659 -0.0103481 -3.15779 -0.0547871 0.0592434 -0.00952148 -0.0456869 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1659 1660 5.42069 -0.481186 -0.478567 0.00933092 0.116507 -0.0341024 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1610 1660 -0.0548329 -3.13305 -0.153966 0.0520365 0.0111749 -0.0298809 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1660 1661 5.72129 -0.0861371 -0.0544607 -0.0102156 0.10542 -0.0130278 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1611 1661 -0.0671868 -3.33123 -0.0408857 0.0703234 -0.015364 -0.0474052 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1661 1662 5.52541 -0.248406 -0.425005 -0.0198206 0.0909803 -0.0786283 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1612 1662 0.140147 -2.82919 -0.171349 0.0719486 0.00466138 -0.0207814 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1662 1663 5.60399 -0.138925 -0.218597 -0.0110683 0.104951 -0.0288543 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1613 1663 -0.0396074 -2.93462 -0.184178 0.0590053 -0.0013146 0.00881843 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1663 1664 5.63845 -0.206175 -0.164425 -0.00824896 0.101925 -0.101831 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1614 1664 -0.110135 -3.04507 0.0684345 0.0806635 0.00947116 -0.0764552 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1664 1665 5.48893 -0.172662 -0.354478 -0.0131798 0.0969381 -0.0105414 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1615 1665 -0.00200346 -3.0994 0.052167 0.043864 0.00934771 0.00480478 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1665 1666 5.60033 -0.117329 -0.276369 0.000746666 0.0918276 -0.0506355 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1616 1666 -0.00590666 -2.91518 -0.0742091 0.0581915 3.59225e-05 0.0271654 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1666 1667 5.31158 -0.302827 -0.257372 -0.00469752 0.113483 -0.0782334 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1617 1667 0.0460345 -3.09381 -0.0892004 0.0739722 0.0189058 -0.0105247 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1667 1668 5.30232 -0.248693 -0.609168 0.00399492 0.108062 -0.123087 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1618 1668 -0.0160461 -3.08989 -0.20474 0.0399664 0.0133005 -0.0661245 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1668 1669 5.41677 -0.211496 -0.2647 -0.000299844 0.119286 -0.0386435 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1619 1669 0.0475918 -3.05535 -0.120123 0.0661918 0.00667878 -0.0267463 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1669 1670 5.46626 -0.0506232 -0.434064 0.00498049 0.100567 -0.0458024 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1620 1670 0.160021 -3.10133 -0.0992102 0.0577509 -0.0181986 -0.0203886 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1670 1671 5.52434 -0.137252 -0.341014 -0.0104677 0.0975904 -0.0226001 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1621 1671 -0.175509 -2.99319 0.148156 0.0534119 0.0129769 0.0280177 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1671 1672 5.38058 -0.302676 -0.0714206 -0.0128491 0.113251 -0.0194697 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1622 1672 0.0694192 -3.16129 -0.0963938 0.0667254 -0.00979451 -0.0309278 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1672 1673 5.45055 -0.173234 -0.296356 -0.000592449 0.0965307 -0.0183261 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1623 1673 -0.0428872 -2.81883 -0.291116 0.0622938 -0.00688944 -0.0118973 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1673 1674 5.47176 -0.421152 -0.336756 0.00706709 0.118123 -0.021886 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1624 1674 -0.0375019 -3.02594 -0.0849859 0.0560455 -0.0198905 0.0233997 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1674 1675 5.48972 -0.260733 -0.242777 -0.0157526 0.112245 -0.0626784 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1625 1675 -0.0517798 -3.06874 -0.308725 0.0649374 -0.00821055 -0.0277186 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1675 1676 5.18825 -0.287163 -0.161593 0.00552439 0.121365 -0.0118932 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1626 1676 0.0643848 -3.18905 -0.188479 0.0701268 0.00304083 -0.0421675 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1676 1677 5.24264 -0.381415 -0.28704 -0.0119082 0.115904 -0.0588984 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1627 1677 -0.115431 -3.06355 -0.11944 0.0608747 -0.00233747 -0.0338837 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1677 1678 5.36808 -0.522253 -0.296253 -0.0119816 0.122273 -0.0556066 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1628 1678 -0.110637 -3.08698 -0.0296284 0.0729156 -0.00786997 0.0139269 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1678 1679 5.29391 -0.375306 -0.426814 -0.0136422 0.112174 -0.0308639 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1629 1679 0.15098 -2.99992 -0.0210215 0.0427021 0.000205052 -0.0707799 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1679 1680 5.30603 -0.149564 -0.225105 0.00542077 0.119318 -0.124558 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1630 1680 0.0590887 -2.98946 -0.289894 0.0584781 -0.0165178 -0.0400762 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1680 1681 5.43539 -0.216739 -0.279844 -0.0100303 0.114169 -0.0626758 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1631 1681 -0.0725235 -3.25599 -0.0819169 0.0496319 -0.000273978 -0.0130374 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1681 1682 5.39725 -0.296233 -0.22819 -0.0178416 0.113091 -0.0903468 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1632 1682 0.107594 -3.05843 -0.183283 0.0534378 0.011724 -0.0158117 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1682 1683 5.50438 -0.0940604 -0.384976 -0.00665726 0.102489 -0.0654925 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1633 1683 0.0412327 -2.97898 -0.191612 0.0663011 0.0096541 -0.0174495 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1683 1684 5.39524 -0.221685 -0.14542 -0.0111 0.130316 -0.0342428 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1634 1684 -0.118428 -3.04648 8.63391e-05 0.0662929 -0.0126526 -0.0359134 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1684 1685 5.47863 -0.290319 -0.26666 -0.00853284 0.116885 -0.0131467 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1635 1685 -0.0262526 -2.97872 -0.0666303 0.0784035 -0.0144846 0.0231709 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1685 1686 5.40783 -0.263143 -0.175894 0.00415399 0.108542 -0.0806445 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1636 1686 0.00612217 -3.09045 -0.0383116 0.0623278 -0.0097341 0.00739669 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1686 1687 5.43558 -0.392199 -0.311421 -0.00840441 0.109613 -0.077788 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1637 1687 0.061165 -2.83709 -0.02318 0.0742605 -0.0150954 -0.0140377 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1687 1688 5.30549 -0.266912 -0.536441 -0.00100288 0.112194 -0.0535861 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1638 1688 -0.202789 -3.12508 -0.061688 0.056443 0.00677952 0.0203563 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1688 1689 5.40989 -0.0817816 -0.146584 -0.00350565 0.103753 -0.0778912 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1639 1689 0.102684 -3.05348 -0.159201 0.068554 0.00590927 -0.0599095 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1689 1690 5.43296 -0.096869 -0.280769 -0.00255301 0.109075 -0.00396185 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1640 1690 -0.123522 -3.07836 -0.0645511 0.0496427 -0.00145858 0.0784978 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1690 1691 5.28814 -0.373082 -0.575759 -0.0036033 0.113473 -0.179572 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1641 1691 -0.214862 -3.04197 0.0174581 0.0478059 -0.00651916 -0.000340415 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1691 1692 5.33409 -0.22076 -0.218809 -0.00853651 0.113742 -0.0647997 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1642 1692 -0.0999051 -3.14174 -0.0649029 0.0790391 0.000303399 0.00640238 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1692 1693 5.3397 -0.135899 -0.339108 0.00488595 0.105167 -0.101286 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1643 1693 -0.0270549 -3.09517 0.0979253 0.0521506 0.00031477 -0.0142848 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1693 1694 5.39282 -0.0952923 -0.251287 0.005865 0.110969 -0.0707873 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1644 1694 0.251858 -3.13504 -0.0540823 0.052765 0.00615171 0.0093411 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1694 1695 5.22027 -0.247357 -0.328483 -0.00466415 0.117178 0.0409995 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1645 1695 0.0632309 -3.10388 -0.143395 0.0639042 0.0173622 -0.0326657 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1695 1696 5.26518 -0.167352 -0.412785 0.00966509 0.109422 -0.0921209 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1646 1696 -0.0132941 -3.06547 0.155902 0.0627379 0.00394893 0.0536723 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1696 1697 5.24761 -0.303176 -0.339079 -0.00793687 0.102205 0.00146887 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1647 1697 0.15223 -3.0546 0.0286233 0.0557066 -0.00211994 0.0583085 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1697 1698 5.31741 -0.07745 -0.215945 -0.00178904 0.117647 -0.00358666 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1648 1698 -0.00535924 -2.83381 -0.140466 0.0682319 -0.0181336 0.00634813 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1698 1699 5.4001 -0.324897 -0.213265 -0.00251519 0.11234 -0.0033435 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1649 1699 0.118396 -3.08906 0.0453904 0.0573686 -0.00401473 0.0640535 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1699 1700 5.31005 -0.212246 -0.0792141 -0.00872768 0.114238 -0.0389002 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1650 1700 -0.00102611 -3.14787 -0.167715 0.0488781 -0.0151907 -0.0430835 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1700 1701 5.32973 -0.20021 -0.263265 -0.00287997 0.110193 -0.0491445 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1651 1701 -0.0433758 -2.96061 0.0751878 0.0685861 0.00402185 -0.00999983 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1701 1702 5.37667 -0.158821 -0.385745 0.00759807 0.112303 -0.0616547 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1652 1702 0.11179 -3.12457 -0.364802 0.04401 -0.0123255 0.0637295 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1702 1703 5.37615 -0.269116 -0.350623 0.000168484 0.117107 -0.0109136 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1653 1703 -0.154935 -3.04908 -0.0287741 0.0530416 -0.0213127 0.00707095 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1703 1704 5.21114 -0.263812 -0.0860465 -0.01049 0.0939937 -0.125626 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1654 1704 0.135974 -3.11749 -0.234774 0.0714388 0.0179497 0.0649358 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1704 1705 5.3006 -0.226295 -0.387647 -0.0118594 0.10442 -0.0669425 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1655 1705 0.0437273 -3.16784 -0.196305 0.0563562 0.0143828 0.0346647 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1705 1706 5.35171 -0.137301 -0.279671 0.0138223 0.123434 -0.0268814 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1656 1706 0.0506714 -3.08938 -0.0608264 0.06271 0.00346024 -0.0206133 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1706 1707 5.34153 -0.227327 -0.349089 0.00672268 0.105672 -0.0873741 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1657 1707 0.0812404 -3.04582 -0.0344527 0.0544687 -0.00216403 -0.000556519 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1707 1708 5.15051 -0.193634 -0.419786 -0.0129222 0.101682 -0.0875975 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1658 1708 0.0544718 -3.13966 -0.0445559 0.0692005 -0.00721094 -0.0226742 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1708 1709 5.3675 -0.434195 -0.228045 -0.022604 0.113593 -0.0448314 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1659 1709 -0.0549216 -3.11848 0.0220124 0.0546264 -0.0101745 -0.0459723 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1709 1710 5.21468 -0.223632 -0.158705 -0.000110622 0.10327 -0.0635111 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1660 1710 0.00410954 -2.88244 -0.139973 0.0776505 0.00926517 -0.0156711 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1710 1711 5.35165 -0.192269 -0.328329 -0.0144935 0.107748 -0.134481 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1661 1711 -0.208269 -2.79218 -0.0660456 0.0619961 0.00837778 -0.017742 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1711 1712 5.31447 -0.371108 -0.160969 -0.0246961 0.0900557 -0.138832 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1662 1712 -0.0558018 -3.05597 -0.129454 0.0749731 0.00570612 0.0726595 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1712 1713 5.09853 -0.179806 -0.156039 -0.00233622 0.114513 -0.0685277 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1663 1713 0.0266015 -2.95221 -0.206465 0.0488209 0.00889565 0.0232198 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1713 1714 5.22918 -0.340417 -0.245276 -0.0103863 0.101745 -0.0833775 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1664 1714 -0.0221156 -2.94292 -0.0317615 0.0769271 -0.00259843 -0.0516553 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1714 1715 5.34764 -0.145038 -0.320751 -0.0111109 0.109721 -0.021115 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1665 1715 0.0581985 -3.07787 -0.0319369 0.0710848 -0.0139158 0.0985367 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1715 1716 5.21627 -0.277662 -0.318961 0.00749723 0.0880979 -0.0550252 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1666 1716 0.0506571 -3.02512 -0.0852228 0.0427903 -0.0134995 0.0130409 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1716 1717 5.46677 -0.192156 -0.254347 -0.00247721 0.118075 -0.118221 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1667 1717 0.077404 -3.0042 -0.107131 0.0786723 -0.00227383 0.0321633 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1717 1718 5.12361 -0.182455 -0.311828 -0.0052538 0.096407 -0.0909123 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1668 1718 0.0409891 -3.05918 0.0264745 0.045631 0.00669727 0.00281707 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1718 1719 5.15102 -0.340883 -0.248257 -0.00522952 0.118697 -0.0599244 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1669 1719 0.108854 -3.03893 -0.0885588 0.0577416 -0.0204497 -0.0250257 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1719 1720 5.1014 -0.305378 -0.135992 -0.0235389 0.107511 -0.0544182 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1670 1720 0.155178 -2.92992 -0.0914363 0.0521235 0.00990708 0.0406062 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1720 1721 5.09683 -0.30535 -0.338787 -0.00779872 0.124067 -0.0339609 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1671 1721 0.0784795 -2.79313 -0.310891 0.049882 -0.0159659 -0.00936441 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1721 1722 5.23714 -0.322653 -0.234773 -0.00242734 0.113848 -0.0641167 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1672 1722 0.139524 -3.07754 -0.153381 0.0482207 -0.013061 0.034499 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1722 1723 5.22082 -0.117568 -0.246577 -0.0120677 0.0996088 -0.0711965 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1673 1723 -0.130169 -3.03599 -0.273301 0.0520484 0.00692607 0.00524426 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1723 1724 5.3624 -0.365673 -0.274439 0.00251912 0.0941435 -0.0844526 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1674 1724 0.0779968 -3.1295 0.00196105 0.0851071 -0.000128804 0.120796 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1724 1725 5.37723 -0.142066 -0.0682578 -0.0042974 0.115647 -0.0729801 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1675 1725 -0.0435085 -3.10494 -0.320083 0.0848444 0.021352 0.0667564 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1725 1726 5.23363 -0.300123 -0.344702 -0.00255536 0.116403 -0.0808624 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1676 1726 -0.0301303 -2.9805 -0.214438 0.0574105 0.00595831 0.0523378 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1726 1727 5.28022 -0.266609 -0.314112 -0.0237049 0.0969272 -0.0415865 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1677 1727 -0.0183632 -3.19129 -0.00449826 0.0575552 -0.00375288 0.00847265 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1727 1728 5.25237 -0.14767 -0.327057 0.0031337 0.101626 -0.0452932 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1678 1728 0.111327 -3.07551 -0.0892905 0.0525536 0.0143075 -0.0285053 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1728 1729 5.41879 -0.238739 -0.181582 0.00604898 0.109823 -0.0949593 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1679 1729 -0.0589236 -3.02074 0.0763044 0.075601 0.0041462 -0.0342464 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1729 1730 5.38416 -0.108165 -0.258329 -0.00526292 0.10416 -0.0508566 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1680 1730 -0.0988038 -3.07371 -0.108336 0.0748652 -0.0146594 -0.0327911 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1730 1731 5.27998 -0.339819 -0.244178 -0.0257112 0.121404 -0.0603909 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1681 1731 -1.00753e-05 -2.92608 -0.106771 0.0740366 -0.0114927 0.0323707 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1731 1732 5.20375 -0.172093 -0.143254 -0.0116436 0.0910198 -0.0500723 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1682 1732 0.0997533 -2.99329 -0.129506 0.0518241 0.0215475 0.0241953 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1732 1733 5.36092 -0.113734 -0.209393 -0.0151156 0.108803 -0.0361898 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1683 1733 -0.0855856 -3.06501 0.0632772 0.054403 -0.0133323 -0.054223 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1733 1734 5.00381 -0.183795 -0.27611 0.0214675 0.0969569 -0.0730745 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1684 1734 -0.0372099 -3.0216 -0.239376 0.0554562 -0.00653835 -0.0796314 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1734 1735 5.15945 -0.388414 -0.377163 -0.0127909 0.0959744 -0.0911948 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1685 1735 -0.0751894 -3.03127 -0.0171367 0.0702485 -0.00316761 -0.0179208 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1735 1736 5.13365 -0.344961 -0.269009 -0.0248953 0.115518 -0.120135 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1686 1736 0.0683954 -3.05474 -0.0261658 0.0664722 -0.0024304 0.003431 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1736 1737 5.34535 -0.355494 -0.313169 -0.0120609 0.0891939 -0.121664 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1687 1737 0.0897784 -2.94217 -0.106125 0.0512759 -0.00830643 0.0132204 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1737 1738 5.1421 -0.149039 -0.236403 0.00496833 0.0957299 -0.0839081 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1688 1738 -0.0233192 -3.20379 0.0603546 0.0476192 0.00335686 0.044507 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1738 1739 5.26696 -0.210099 -0.538185 0.00125349 0.098402 -0.0823363 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1689 1739 0.0312816 -3.02489 -0.125454 0.0498953 0.00227936 -0.0342217 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1739 1740 5.11757 -0.240167 -0.202272 0.000225482 0.0918612 -0.0856793 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1690 1740 0.050222 -3.08711 -0.260233 0.0536449 -0.000627557 -0.00562751 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1740 1741 5.09557 -0.261468 -0.226319 -0.0165765 0.105763 -0.0712561 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1691 1741 0.000232103 -3.12867 -0.0661392 0.052384 -0.0102861 0.0153483 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1741 1742 5.1509 -0.31557 -0.33131 -0.0178079 0.110371 -0.0635718 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1692 1742 -0.00234648 -3.00674 -0.064097 0.0712402 -0.00768645 0.0672575 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1742 1743 5.05177 -0.271059 -0.220028 -0.000639199 0.102502 -0.051658 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1693 1743 0.0151753 -2.96066 -0.0288111 0.0821135 -0.00185153 0.025916 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1743 1744 5.17976 -0.309352 -0.346285 -0.00847352 0.096469 -0.0601704 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1694 1744 0.0376473 -3.11896 0.159874 0.0753405 0.0138827 0.0268798 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1744 1745 5.08443 -0.232754 -0.192742 -0.0157728 0.104767 -0.00356622 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1695 1745 -0.00373479 -2.95707 -0.035569 0.0556143 -0.0116211 -0.00392871 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1745 1746 5.06282 -0.148988 -0.108716 -0.00615296 0.100331 -0.0398386 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1696 1746 -0.144719 -3.07335 0.0154428 0.0638846 -0.0281165 0.0281369 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1746 1747 5.13999 -0.351509 -0.28481 -0.00315093 0.100755 -0.0257939 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1697 1747 0.0831829 -2.96305 -0.19567 0.0707313 0.0016152 0.0621866 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1747 1748 5.10221 -0.208006 -0.111125 0.000933293 0.0990091 -0.0491483 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1698 1748 0.0399274 -3.04172 -0.0943693 0.0556363 0.00446933 0.0138841 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1748 1749 5.19163 -0.316871 -0.0556211 -0.00661727 0.0947991 -0.119547 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1699 1749 -0.0447719 -3.14214 -0.068291 0.0429456 0.000466281 -0.0298963 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1749 1750 4.96233 -0.0370499 -0.338332 0.00655668 0.110331 -0.0988197 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1700 1750 0.0294699 -3.11978 -0.0135458 0.0605065 0.0182167 0.0120151 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1750 1751 5.13469 -0.168774 -0.208992 -0.0211247 0.102718 -0.0321316 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1701 1751 -0.224595 -3.0665 -0.0867665 0.0639967 -0.00473644 -0.0232712 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1751 1752 5.05912 -0.0357039 -0.0785567 -0.0203671 0.106647 -0.101273 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1702 1752 -0.0987004 -3.09572 -0.168813 0.0610131 -0.00065001 -0.0102696 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1752 1753 5.18405 -0.16026 -0.226098 -0.00242535 0.103807 -0.0744918 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1703 1753 0.0928793 -3.01206 -0.00747065 0.0655767 0.00581311 0.00957212 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1753 1754 5.15883 -0.336766 -0.316554 0.00359139 0.0884198 -0.0759128 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1704 1754 0.136436 -3.29781 -0.010292 0.070665 0.00556715 -0.0138147 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1754 1755 4.94534 -0.154155 -0.15906 0.0117564 0.0970189 -0.0871264 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1705 1755 -0.0985199 -2.9693 0.130487 0.0520932 -0.013393 0.00759027 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1755 1756 5.02992 -0.316172 -0.225531 -0.0046333 0.0966119 -0.0112592 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1706 1756 -0.0243237 -3.13349 -0.0924315 0.065697 0.0123383 0.048212 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1756 1757 5.03435 -0.277086 -0.254374 3.57966e-06 0.0783776 -0.107226 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1707 1757 0.038385 -3.1399 -0.0395141 0.0553597 0.000830794 -0.0713513 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1757 1758 4.918 -0.183459 -0.33853 0.00231255 0.124888 -0.0310429 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1708 1758 -0.0217017 -2.9289 -0.0520931 0.0599912 -0.00831103 -0.00798498 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1758 1759 5.0202 -0.258962 -0.319223 0.0081808 0.104246 -0.106029 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1709 1759 0.02184 -3.07267 -0.118739 0.0654458 0.00755739 0.0503701 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1759 1760 5.09639 -0.0864276 -0.231226 -0.0211054 0.0807318 -0.0707132 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1710 1760 0.0835784 -3.02283 -0.212193 0.0521434 -0.0170137 0.0203284 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1760 1761 5.11283 -0.375161 -0.165648 -0.0271125 0.0947828 -0.0889622 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1711 1761 0.0616834 -3.16791 -0.119757 0.0595417 0.0107941 0.0377087 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1761 1762 5.16159 -0.228799 -0.251336 -0.0126219 0.119838 -0.110506 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1712 1762 -0.0229592 -2.96465 -0.0271811 0.0533317 -0.00719889 -0.0263462 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1762 1763 5.18125 -0.27907 -0.271409 -0.00428465 0.0986156 -0.153796 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1713 1763 0.0254188 -3.035 -0.087917 0.0618986 0.00247026 -0.0778262 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1763 1764 5.04027 -0.203104 -0.169254 0.00279834 0.0937873 -0.0783212 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1714 1764 -0.0385847 -3.06702 -0.000142204 0.0766439 0.0086413 -0.036947 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1764 1765 5.12174 -0.236564 -0.215704 -0.00714981 0.114455 -0.0529487 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1715 1765 -0.0373318 -2.9153 -0.0751231 0.067205 -0.00803852 0.0710451 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1765 1766 5.26865 -0.233047 -0.208571 -0.00889891 0.105851 -0.0735401 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1716 1766 0.0665495 -3.08995 -0.0838247 0.0419185 -0.00357765 -0.00864219 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1766 1767 5.11228 -0.199159 -0.253987 -0.00393215 0.102707 -0.0869522 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1717 1767 0.115077 -3.11648 -0.0208489 0.0590557 0.00787203 -0.0181757 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1767 1768 5.12173 -0.184384 -0.282995 -0.0193505 0.0846426 -0.0764836 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1718 1768 -0.152788 -3.07458 -0.0430562 0.0588557 0.0114501 -0.0152301 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1768 1769 5.02767 -0.344458 -0.310333 -0.0190489 0.108258 -0.0759524 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1719 1769 0.0290396 -2.93778 -0.174998 0.0586799 0.000185658 -0.0514896 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1769 1770 5.09559 -0.0512366 -0.271712 -0.0215205 0.0966126 -0.108596 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1720 1770 0.0872993 -3.17508 -0.300186 0.069219 -0.00729303 -0.0136273 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1770 1771 5.11342 -0.280845 -0.207459 0.00802989 0.0992093 -0.0205482 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1721 1771 -0.0808485 -2.98209 0.0666504 0.0571862 -0.0170698 0.025118 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1771 1772 5.17651 -0.306526 -0.253489 -0.0076864 0.100045 -0.0697205 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1722 1772 -0.0741631 -3.10956 -0.357373 0.0438161 0.016262 0.0270955 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1772 1773 5.11425 -0.225281 -0.230751 0.00489981 0.10891 -0.0410992 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1723 1773 -0.0024191 -3.04392 -0.13162 0.0654803 -0.00389728 0.0342213 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1773 1774 4.94863 -0.196555 -0.208993 -0.0169112 0.091039 -0.0534657 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1724 1774 -0.061164 -3.11648 -0.101092 0.0597395 -0.000715408 0.00704871 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1774 1775 5.06016 -0.20434 -0.0522081 -0.00848024 0.101393 -0.0882082 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1725 1775 0.0422005 -3.21286 -0.101498 0.051245 0.000673453 0.0488583 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1775 1776 5.10048 -0.309485 -0.109571 -0.0065981 0.10455 -0.0625986 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1726 1776 -0.0693445 -2.94606 0.00886117 0.0621589 0.00580464 0.0569154 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1776 1777 4.98326 -0.158293 -0.304665 0.00892294 0.100281 -0.0825051 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1727 1777 0.0283331 -3.04883 -0.0458735 0.055171 -0.0234592 -0.0263705 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1777 1778 5.07 -0.171504 -0.110436 -0.00229188 0.113286 -0.0761549 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1728 1778 0.0956368 -3.06028 -0.115547 0.0611168 -0.00355672 0.0148993 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1778 1779 5.19136 -0.287359 -0.306423 0.000523697 0.110397 -0.0877705 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1729 1779 -0.0217363 -2.95882 -0.147397 0.0513307 0.00683968 0.00219447 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1779 1780 5.0023 -0.344019 -0.126438 -0.00329916 0.100815 -0.0913329 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1730 1780 0.0993559 -3.08697 -0.146995 0.0711057 0.000420213 -0.0240329 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1780 1781 5.0345 -0.482599 -0.148384 0.00983611 0.102309 -0.0336878 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1731 1781 0.269392 -3.16796 -0.106407 0.0614438 0.000933647 -0.0873864 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1781 1782 4.92071 -0.324862 -0.241897 0.00135277 0.0816579 -0.0972105 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1732 1782 0.0567221 -3.09554 -0.117844 0.0579469 0.0188528 0.0401364 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1782 1783 4.82176 -0.337135 -0.0834293 0.0144756 0.0937229 -0.0114978 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1733 1783 -0.0383315 -3.05183 -0.165114 0.0806398 0.00921275 -0.029123 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1783 1784 5.05136 -0.257181 -0.317027 -0.00288921 0.101461 -0.0964022 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1734 1784 0.0273392 -3.22064 -0.0606707 0.0471434 0.0119806 -0.0591094 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1784 1785 4.89393 -0.181988 -0.298799 -0.000145038 0.126299 -0.0134191 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1735 1785 0.0179814 -3.19759 -0.0163119 0.0762702 0.0104228 -0.020123 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1785 1786 5.0384 -0.128486 -0.212315 0.0123447 0.100283 -0.0807534 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1736 1786 -0.0580247 -3.14452 -0.0615037 0.0506813 -0.00878618 -0.0378451 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1786 1787 5.02545 -0.460312 -0.180722 -0.019587 0.0858189 -0.0222926 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1737 1787 -0.0142271 -2.91858 -0.216564 0.0617981 -0.0109615 0.0693965 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1787 1788 4.83218 -0.198488 -0.344257 -0.00615943 0.0987421 -0.0695063 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1738 1788 0.0322481 -3.35482 -0.0579082 0.0517647 -0.00869215 -0.0415983 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1788 1789 4.90438 -0.208304 -0.292683 -0.018938 0.0827866 -0.0553459 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1739 1789 -0.107296 -3.17349 -0.00766549 0.0452655 -0.0115544 -0.0189254 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1789 1790 5.09904 -0.261975 -0.275921 -0.00798948 0.101937 -0.0826196 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1740 1790 -0.0283242 -3.10696 -0.151051 0.0808494 -0.0199533 0.0043042 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1790 1791 4.92126 -0.296514 -0.183025 -0.0027896 0.0920821 -0.0972734 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1741 1791 0.129306 -3.07778 -0.0748081 0.0680715 0.0324997 -0.00785929 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1791 1792 4.92158 -0.187052 -0.278332 -0.00171466 0.0893782 -0.0491221 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1742 1792 0.0474685 -3.21232 -0.076853 0.0570036 0.00561036 0.020444 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1792 1793 4.98289 -0.235286 -0.136228 0.00142005 0.106536 -0.139555 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1743 1793 0.0387287 -3.04757 -0.152162 0.0675135 -0.0161684 -0.0485659 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1793 1794 4.95651 -0.211982 -0.330773 -0.0129083 0.109445 -0.0489901 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1744 1794 0.109502 -3.01428 -0.0774052 0.0626841 -0.00164219 -0.0207031 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1794 1795 4.90502 -0.40185 -0.176247 0.00303706 0.118182 -0.105131 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1745 1795 -0.00973706 -3.02964 -0.146674 0.0705599 -0.00153592 -0.0494031 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1795 1796 4.98873 -0.090772 -0.125356 0.00267283 0.0968311 -0.090112 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1746 1796 -0.216773 -2.97528 -0.322252 0.0536997 0.0110756 0.0888586 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1796 1797 4.75329 -0.0154757 -0.10417 0.00243186 0.0985611 -0.0735988 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1747 1797 0.118012 -3.03699 -0.104414 0.0640525 -0.0279547 0.0438113 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1797 1798 4.92674 -0.109837 -0.138109 0.0160474 0.0958195 -0.11533 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1748 1798 -0.0150702 -3.06263 -0.131972 0.0633138 -0.0113576 0.0081699 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1798 1799 4.90501 -0.347689 -0.231813 0.00569333 0.0983242 -0.135091 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1749 1799 0.0492402 -3.07448 -0.168954 0.075632 -0.0294492 -0.0414156 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1799 1800 4.77922 -0.223 -0.165329 -0.00747573 0.0908522 -0.0747077 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1750 1800 0.182859 -3.05399 -0.0975698 0.0572889 0.000289157 -0.0183538 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1800 1801 5.09266 -0.282487 -0.304662 -0.0108894 0.10383 0.0150758 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1751 1801 -0.152133 -3.16877 -0.149779 0.0649602 -0.0129182 -0.00521459 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1801 1802 4.97544 -0.211475 -0.223103 -0.0023098 0.0949104 -0.191431 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1752 1802 0.125603 -3.09023 -0.0306891 0.0616846 0.00807663 0.0223447 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1802 1803 4.77412 -0.318084 0.0552795 -0.0165723 0.0905459 -0.0305154 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1753 1803 -0.0365699 -3.04003 -0.15614 0.0692653 0.000997783 -0.0163272 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1803 1804 4.80861 -0.26475 -0.388229 -0.0159291 0.0825196 -0.104522 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1754 1804 0.0302507 -3.08727 -0.270373 0.0583092 -0.0160674 -0.034554 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1804 1805 4.88532 -0.165758 -0.228279 -0.00501391 0.0972952 -0.0472278 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1755 1805 0.0189872 -3.05832 -0.242167 0.0624271 -0.00301431 -0.00764289 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1805 1806 4.9284 -0.132573 -0.231986 -0.0122576 0.113036 -0.0439441 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1756 1806 -0.012015 -3.03427 -0.124307 0.0703052 -0.00725931 0.0189767 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1806 1807 4.77373 -0.360763 -0.212926 0.00205494 0.0947878 -0.0831569 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1757 1807 0.0375861 -3.06606 -0.22404 0.0762869 -0.00250805 0.0331713 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1807 1808 4.85952 -0.260821 -0.139659 -0.0153147 0.0892659 -0.145059 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1758 1808 -0.0955637 -2.97001 0.115194 0.0647913 -0.0138467 -0.0826333 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1808 1809 4.82634 -0.171044 -0.203148 -0.0176003 0.0944871 -0.0478894 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1759 1809 -0.114555 -2.943 -0.0308129 0.0683268 -0.00557105 0.0175325 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1809 1810 4.95183 -0.208995 -0.101037 -0.0179122 0.0973581 -0.0989459 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1760 1810 0.0123224 -3.24788 -0.212326 0.0483225 0.00452046 -0.0171185 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1810 1811 4.79758 -0.32531 -0.122337 -0.000533753 0.104216 -0.0920073 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1761 1811 -0.0408912 -3.00739 0.0422893 0.0794163 0.00520002 0.0158059 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1811 1812 4.91477 -0.120461 -0.40838 -0.0182614 0.0959427 -0.00513937 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1762 1812 0.219922 -3.03153 0.0134531 0.0654384 0.00485157 -0.00673817 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1812 1813 4.81165 -0.271805 -0.288145 -0.00286115 0.0959124 -0.0651372 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1763 1813 -0.0222045 -3.08264 -0.211468 0.0708378 0.00405578 -0.00728253 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1813 1814 5.01526 -0.396095 -0.225831 0.00706039 0.103839 -0.074546 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1764 1814 0.0415692 -2.96824 -0.000418305 0.0499308 -0.00767938 -0.0594156 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1814 1815 4.87234 -0.130062 -0.269351 -0.0219584 0.106965 -0.0241689 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1765 1815 -0.062842 -3.11635 -0.0526797 0.0592243 -0.006188 0.00441467 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1815 1816 4.88553 -0.28768 -0.145095 -0.005929 0.0933327 -0.0792619 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1766 1816 -0.0287574 -3.03978 -0.231726 0.0506148 -0.0138973 0.0436976 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1816 1817 4.75327 -0.0974786 -0.203379 0.00488044 0.0865973 -0.148864 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1767 1817 0.0282841 -2.93195 -0.09693 0.0773798 -0.0132547 0.0211111 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1817 1818 4.7098 -0.268331 -0.263478 0.0186111 0.0889934 -0.0865322 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1768 1818 -0.0435599 -2.97465 -0.14503 0.0449447 -0.012731 0.0820732 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1818 1819 4.82591 -0.266342 -0.438479 0.0045304 0.0862127 -0.11871 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1769 1819 0.0680926 -2.90573 -0.211321 0.0519969 -0.00144775 -0.0135646 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1819 1820 4.83841 -0.161507 -0.0770926 -0.0072428 0.102658 -0.0999522 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1770 1820 0.0616235 -3.05767 -0.126215 0.0541905 0.0195727 -0.0169415 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1820 1821 4.97919 -0.447477 -0.280722 -0.00136713 0.0737957 -0.109513 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1771 1821 -0.10416 -3.02821 -0.057326 0.054687 0.0024022 0.0511145 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1821 1822 4.85974 -0.317102 -0.480157 0.0193524 0.10041 -0.0435742 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1772 1822 0.192023 -2.87943 -0.114734 0.0511578 -0.000645648 -0.0339111 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1822 1823 4.83929 -0.238797 -0.319069 0.000335712 0.0992771 -0.119442 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1773 1823 -0.178231 -3.0507 -0.0438601 0.0483637 -0.010466 -0.0372206 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1823 1824 4.78394 -0.403704 -0.205208 -0.0137986 0.112579 -0.17247 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1774 1824 -0.0987786 -3.0068 0.0045094 0.0677603 0.00353463 0.038038 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1824 1825 4.81702 -0.348762 -0.265972 -0.0138826 0.108581 -0.0580538 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1775 1825 -0.0648302 -2.8894 0.0399057 0.0632194 0.00959133 0.0814225 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1825 1826 4.81675 -0.24492 -0.117994 -0.0050721 0.096936 -0.0792821 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1776 1826 -0.0078235 -3.08813 -0.181108 0.0590393 -0.0140913 -0.0173059 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1826 1827 4.89557 -0.361056 -0.307536 -0.00451122 0.0921269 -0.067931 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1777 1827 -0.122792 -3.09499 -0.100944 0.0577895 -0.0130607 -0.0319942 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1827 1828 4.75582 -0.271349 -0.15809 -0.00711898 0.0896873 -0.112515 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1778 1828 0.0388573 -3.02131 -0.00652277 0.0699269 0.00239921 -0.00742824 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1828 1829 4.73049 -0.294431 -0.301175 -0.000526391 0.0832795 -0.167077 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1779 1829 -0.000309022 -2.90919 -0.0208505 0.0695055 0.0112504 -0.0158502 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1829 1830 4.92886 -0.130165 -0.165002 -0.00368411 0.11642 -0.0336335 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1780 1830 -0.108461 -3.1802 -0.18677 0.0527164 -0.00321506 0.0381845 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1830 1831 4.6298 -0.435083 -0.137867 -0.001988 0.0936441 -0.0641449 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1781 1831 0.140164 -2.96356 -0.014656 0.0670866 -0.0031135 -0.0168279 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1831 1832 4.74803 -0.151841 -0.288237 0.00829702 0.102145 -0.0820254 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1782 1832 -0.012127 -2.9899 -0.0295551 0.0853943 -0.000852896 -0.00686466 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1832 1833 4.85339 -0.343561 -0.169301 -0.00163656 0.0984554 -0.0891252 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1783 1833 -0.0144925 -3.00285 0.0284105 0.0498564 0.00939331 -0.0142215 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1833 1834 4.54808 -0.392319 -0.214532 -0.0152504 0.0951623 -0.0283661 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1784 1834 0.222172 -3.02502 -0.029758 0.0608715 0.0120433 -0.0150827 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1834 1835 4.64417 -0.311206 -0.476396 -0.00560264 0.0966071 -0.0407182 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1785 1835 -0.0482292 -3.04667 0.0326862 0.0683461 -0.00275642 -0.0589991 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1835 1836 4.95349 -0.223524 -0.261534 -0.00795382 0.0943563 -0.0346849 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1786 1836 -0.0335317 -3.04668 -0.0991304 0.0546924 0.00177815 0.000480783 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1836 1837 4.70114 -0.124719 -0.272527 -0.010809 0.102571 -0.0946032 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1787 1837 -0.0626125 -3.03427 0.0676801 0.0516742 -0.00187972 -0.0475634 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1837 1838 4.62714 -0.201168 -0.165333 -0.0100206 0.107918 -0.0331809 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1788 1838 0.0471752 -3.08736 0.05968 0.030737 0.0159755 0.0527381 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1838 1839 4.77426 -0.113355 -0.322589 -0.0143616 0.0943777 -0.0917203 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1789 1839 0.0188436 -3.06368 0.0720668 0.0818474 0.0114799 -0.00345901 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1839 1840 4.61616 -0.293992 -0.216557 0.000582939 0.0886109 -0.121437 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1790 1840 -0.0206358 -3.06349 -0.261491 0.0681527 0.0134471 0.00972475 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1840 1841 4.67614 -0.295208 -0.313561 -0.00382282 0.117662 -0.090094 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1791 1841 0.0958677 -3.05315 -0.22173 0.0458412 0.00462257 -0.0468129 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1841 1842 4.61225 -0.179533 -0.271756 -0.0149073 0.114372 -0.0772276 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1792 1842 -0.0715469 -3.11082 -0.306459 0.0653106 -0.00790786 0.037411 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1842 1843 4.76378 -0.377619 -0.214941 0.00412791 0.0865911 -0.0728148 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1793 1843 0.0518907 -2.91562 -0.122442 0.043295 0.00439581 -0.086833 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1843 1844 4.75419 -0.359341 -0.170499 -0.00531465 0.0949683 -0.118355 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1794 1844 -0.0159708 -3.12139 -0.0824815 0.0623852 -0.00142231 -0.0483063 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1844 1845 4.68768 -0.252698 -0.156315 -0.00677702 0.100201 -0.209675 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1795 1845 0.120579 -3.15235 0.146184 0.0437515 0.0034017 -0.0390961 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1845 1846 4.72071 -0.0861133 -0.295451 9.50973e-05 0.100831 -0.0547042 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1796 1846 0.123159 -3.01997 -0.253439 0.0580113 0.00828285 0.0588462 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1846 1847 4.5354 -0.407092 -0.101975 -0.00891557 0.0920906 -0.0191004 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1797 1847 0.144637 -3.16179 -0.265119 0.0764653 -0.00658368 0.0460853 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1847 1848 4.60801 -0.126293 -0.244688 -0.0052939 0.103868 -0.094666 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1798 1848 -0.12162 -2.98479 -0.154439 0.0671829 0.0324719 -0.00283929 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1848 1849 4.61804 -0.109776 0.0579462 0.00955842 0.100207 -0.0700888 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1799 1849 0.132477 -3.03471 -0.145067 0.0609105 0.01149 -0.0127041 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1849 1850 4.77603 -0.15837 -0.10548 0.000827253 0.103943 -0.0752349 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1800 1850 -0.108137 -2.87796 -0.224581 0.0708447 0.000116664 0.00372955 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1850 1851 4.63142 -0.272999 -0.128289 0.00536304 0.0791685 -0.108227 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1801 1851 0.042069 -2.80394 -0.18803 0.0621952 -0.0043172 -0.0157536 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1851 1852 4.68181 -0.0973537 -0.151376 -0.00658094 0.0990499 -0.0917664 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1802 1852 -0.0877699 -3.17664 -0.0572846 0.0479959 0.00962734 0.100438 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1852 1853 4.6503 -0.320069 -0.331807 -0.00976131 0.100877 -0.13558 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1803 1853 -0.0742592 -2.90932 0.0189127 0.0721261 -0.0165091 -0.036432 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1853 1854 4.69398 -0.193299 0.0197714 -0.0176067 0.0909729 -0.0080528 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1804 1854 -0.0383705 -3.16786 -0.0654075 0.0584352 0.0208323 -0.00536037 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1854 1855 4.6655 -0.267701 -0.190265 -0.00211648 0.0865708 -0.0278417 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1805 1855 -0.00902558 -2.92915 -0.120399 0.0591487 -0.00488917 -0.0315146 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1855 1856 4.42177 -0.256342 -0.205254 -0.016843 0.0949576 -0.0944535 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1806 1856 -0.0765701 -3.12898 -0.090606 0.0768918 0.011933 0.0750656 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1856 1857 4.71076 -0.367691 -0.227541 -0.0133918 0.113067 0.000679603 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1807 1857 0.14094 -3.05249 -0.343382 0.0792538 -0.0139568 -0.0145973 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1857 1858 4.50405 -0.294668 -0.26997 -0.0185135 0.101194 -0.0647436 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1808 1858 -0.0761782 -3.09231 -0.0246564 0.072825 -0.0149646 0.0251462 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1858 1859 4.55554 -0.148973 -0.182055 0.00290392 0.0906017 0.0354924 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1809 1859 -0.188033 -2.9272 -0.113857 0.0612109 0.00747083 0.0431749 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1859 1860 4.64651 -0.277451 -0.359388 -0.00926957 0.107963 -0.0562575 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1810 1860 -0.090876 -3.05835 -0.290709 0.0765461 0.00631462 -0.0388976 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1860 1861 4.56676 -0.36899 -0.164651 0.00580102 0.084293 -0.0688952 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1811 1861 0.0526861 -3.07877 -0.169244 0.059532 -0.00797233 -0.0827041 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1861 1862 4.50337 -0.230667 -0.177172 0.0030579 0.0919689 -0.111539 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1812 1862 0.116739 -2.98034 -0.217091 0.0702648 -0.00609367 0.0199529 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1862 1863 4.64065 -0.300941 -0.158616 -0.010913 0.0907156 -0.0926637 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1813 1863 -0.13546 -3.11522 -0.0917262 0.0692889 -0.0125472 0.0151566 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1863 1864 4.59642 -0.254075 -0.0463375 0.017004 0.0800944 -0.149026 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1814 1864 -0.0866169 -3.00286 -0.293697 0.0728429 0.00244369 0.00365238 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1864 1865 4.63337 -0.209633 -0.260197 -0.0123506 0.0894912 -0.0123663 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1815 1865 -0.169136 -3.01777 -0.0343924 0.0739501 -0.0276018 0.0202029 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1865 1866 4.42479 -0.240782 -0.264261 -0.00605098 0.102242 -0.0886238 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1816 1866 0.10855 -3.03261 -0.123647 0.0590287 0.006759 -0.0136211 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1866 1867 4.55391 -0.261659 -0.358861 -0.00253605 0.0808509 -0.0814289 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1817 1867 0.1199 -3.1384 -0.247879 0.0475286 0.00597141 0.031673 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1867 1868 4.55404 -0.030304 -0.261655 0.0110733 0.087561 -0.123222 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1818 1868 0.101038 -3.15884 -0.0424015 0.0570756 0.0125934 0.124163 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1868 1869 4.59594 -0.359304 -0.28261 -0.00562722 0.0929925 -0.0350109 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1819 1869 0.0952807 -2.85621 0.124586 0.0332439 -0.0103211 -0.00109132 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1869 1870 4.78738 -0.167502 -0.151601 0.00195706 0.0897277 -0.10005 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1820 1870 -0.0168166 -3.04721 -0.239359 0.0431807 0.0042476 -0.0155395 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1870 1871 4.56802 -0.129037 -0.20308 0.00238513 0.098059 -0.111834 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1821 1871 0.0803017 -3.02661 -0.191708 0.0635411 0.0149503 -0.0343494 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1871 1872 4.48885 -0.0342608 -0.0181551 0.0193062 0.0753743 -0.0586859 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1822 1872 0.0739379 -2.96847 0.00569321 0.0682755 0.00374356 0.0332516 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1872 1873 4.3311 -0.264852 -0.186083 -0.0110717 0.104062 -0.132561 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1823 1873 -0.0143154 -3.23242 -0.0257429 0.0622019 0.00240997 -0.0137481 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1873 1874 4.49719 -0.261598 0.0532623 0.00122266 0.0922871 -0.093952 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1824 1874 0.0613559 -2.92594 -0.312506 0.0596012 -0.00863976 -0.052485 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1874 1875 4.58532 -0.23031 -0.192696 -0.00494584 0.101564 -0.10779 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1825 1875 0.00772411 -3.10499 -0.0477326 0.0679275 -0.000813983 -0.0185891 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1875 1876 4.35546 -0.339718 -0.169654 -0.0109987 0.0809854 -0.0920165 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1826 1876 0.161524 -3.2491 -0.114827 0.0804324 0.00224102 -0.0176379 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1876 1877 4.54031 -0.244959 -0.267222 0.00241677 0.0762422 -0.0662324 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1827 1877 0.186278 -3.11028 -0.0133621 0.052274 -0.00292716 0.0280542 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1877 1878 4.60547 -0.309716 -0.251823 -0.00599094 0.0954587 -0.179015 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1828 1878 0.0531775 -3.08589 -0.112001 0.0405242 -0.0064053 0.00917279 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1878 1879 4.54325 -0.115893 -0.140441 -0.0146982 0.0978564 -0.0836896 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1829 1879 -0.020543 -3.27013 -0.212735 0.0564147 0.0128103 -0.0760244 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1879 1880 4.52617 -0.302251 -0.37575 -0.00183563 0.108235 -0.158284 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1830 1880 -0.00259814 -3.14464 -0.087878 0.0695936 -0.00956796 -0.0445708 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1880 1881 4.54856 -0.158533 -0.254646 0.00205262 0.0994201 -0.100491 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1831 1881 -0.0893566 -3.07893 -0.18693 0.0610658 0.00073669 0.0440814 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1881 1882 4.35954 -0.288155 -0.211167 0.00745067 0.0837914 -0.0691687 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1832 1882 0.116092 -2.92028 -0.0442224 0.0677234 -0.00204854 0.0439028 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1882 1883 4.56887 -0.0929468 -0.311223 0.000460255 0.0872684 -0.178205 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1833 1883 0.0758564 -3.18104 -0.226805 0.0709626 0.0129886 0.00358545 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1883 1884 4.46033 -0.294934 -0.219197 0.00569462 0.102623 -0.0999751 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1834 1884 -0.084759 -3.22165 0.0114432 0.0499421 -0.0148616 0.00918912 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1884 1885 4.38959 -0.196717 -0.208776 0.00624706 0.0935683 -0.108966 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1835 1885 0.0548894 -2.99025 -0.144123 0.0655518 -0.00423922 -0.0542006 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1885 1886 4.43024 -0.160032 -0.239509 -0.0349875 0.090498 -0.123335 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1836 1886 0.0885277 -3.14703 -0.0265822 0.0579084 0.0137227 0.00905663 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1886 1887 4.50574 -0.253492 -0.131022 -0.00630733 0.0910965 -0.0538159 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1837 1887 0.0218338 -3.13588 -0.113553 0.0668271 0.00372304 -0.0991861 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1887 1888 4.51343 -0.429701 -0.287934 -0.000209637 0.108305 -0.149976 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1838 1888 -0.00821434 -3.17133 0.00805733 0.0666172 -0.00824035 -0.0363585 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1888 1889 4.47962 -0.37622 -0.272483 -0.00789119 0.0813587 -0.06964 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1839 1889 -0.0509058 -2.91188 -0.212373 0.067461 -0.0205428 -0.000182639 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1889 1890 4.34179 -0.0240087 -0.241593 0.00726602 0.0975707 -0.0839039 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1840 1890 -0.0505836 -2.91351 -0.250506 0.08337 -0.00630299 -0.0501471 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1890 1891 4.35205 -0.16348 -0.20882 -0.0123174 0.087271 -0.0518578 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1841 1891 -0.129239 -3.18183 -0.230686 0.0538964 -0.000225464 -0.0838791 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1891 1892 4.30193 -0.281841 -0.088496 -0.00954845 0.0929985 -0.157635 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1842 1892 -0.0535983 -2.92779 -0.0518271 0.0799358 0.0142019 -0.00681962 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1892 1893 4.21476 -0.111473 -0.192084 -0.0180358 0.0735265 -0.0606514 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1843 1893 0.0324093 -3.19663 -0.0408329 0.0612652 -0.00871208 -0.04819 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1893 1894 4.4421 -0.337322 -0.22283 -0.000882865 0.0823614 -0.0208079 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1844 1894 -0.0770178 -3.16532 -0.0640183 0.0707633 -0.00977542 -0.0208785 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1894 1895 4.38043 -0.385174 -0.169445 0.00567405 0.101163 -0.0937427 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1845 1895 -0.0234045 -3.15978 -0.0221831 0.0646353 -0.0128911 0.0948391 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1895 1896 4.31434 -0.270794 -0.282302 0.00240869 0.0900273 -0.0768036 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1846 1896 -0.0843723 -3.00494 0.000423335 0.0531676 -0.0111417 -0.0622419 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1896 1897 4.44356 -0.29539 -0.240215 -0.0141811 0.0836801 -0.0817204 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1847 1897 0.191385 -2.92016 -0.208971 0.0585519 0.00772875 0.0571633 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1897 1898 4.46323 -0.226667 -0.147095 0.0140399 0.0697035 -0.121016 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1848 1898 0.202927 -3.05126 -0.142374 0.0555069 0.0103147 -0.011735 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1898 1899 4.31549 -0.306274 -0.332723 0.0109474 0.0945646 -0.0817513 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1849 1899 0.0403644 -3.03129 -0.0179074 0.0614092 -0.00291469 0.028469 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1899 1900 4.18451 -0.150939 -0.40337 -0.00138186 0.0876948 -0.0471816 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1850 1900 0.0957077 -3.01279 -0.044987 0.0506446 -0.000660243 -0.019608 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1900 1901 4.3209 -0.0123597 -0.102028 9.83534e-05 0.0922107 -0.051044 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1851 1901 -0.174056 -3.04715 -0.111642 0.0621035 -0.00755424 0.0135644 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1901 1902 4.319 -0.192356 -0.0337542 -0.0182751 0.0833723 -0.0809759 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1852 1902 0.0680705 -3.14048 -0.178702 0.0607085 0.0135957 -0.00229303 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1902 1903 4.41828 -0.0962022 -0.211985 -0.00995988 0.0744657 -0.110466 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1853 1903 0.00378761 -3.16236 -0.141362 0.0591533 0.00509642 -0.0140452 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1903 1904 4.25658 -0.12072 -0.0793969 0.00515729 0.0963357 -0.00792459 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1854 1904 0.095026 -2.88379 -0.278144 0.0622662 0.00417311 0.0479794 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1904 1905 4.25253 -0.242802 -0.268575 0.0113678 0.0943997 -0.0600259 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1855 1905 -0.32096 -3.21696 -0.1433 0.0553023 0.0075246 -0.00153905 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1905 1906 4.49917 -0.266086 -0.377066 -0.0152041 0.0946548 -0.193306 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1856 1906 -0.0141632 -2.94756 -0.266488 0.0727217 0.00277965 -0.0160306 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1906 1907 4.31382 -0.267079 -0.208264 -0.000243839 0.0892815 -0.114627 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1857 1907 0.123448 -3.11809 -0.0386667 0.0618456 0.0068748 -0.0346133 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1907 1908 4.45144 -0.365909 -0.312542 -0.013901 0.0890966 -0.112512 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1858 1908 0.175612 -3.00971 0.0343817 0.0670299 -0.000263977 0.0405356 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1908 1909 4.26669 -0.274093 -0.135733 -0.0133767 0.0888738 -0.0922154 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1859 1909 -0.0143492 -3.03281 -0.191016 0.0633778 0.0168929 0.048693 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1909 1910 4.24691 -0.11138 -0.14229 0.000229511 0.0858012 -0.0592783 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1860 1910 -0.0958643 -3.07388 0.0497909 0.0470989 0.00508015 -0.0126608 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1910 1911 4.22629 -0.253439 -0.157639 0.00267606 0.0815736 -0.075993 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1861 1911 -0.0332655 -2.95962 0.0264198 0.0576656 -0.00461829 0.00380271 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1911 1912 4.2983 -0.148176 -0.101345 -0.00615889 0.0695333 -0.11309 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1862 1912 -0.0801627 -3.03279 -0.126231 0.066146 -0.000662345 0.0254509 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1912 1913 4.29847 -0.247014 -0.216417 0.00466853 0.0894955 -0.167794 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1863 1913 -0.0067682 -2.99896 -0.114812 0.0652925 -0.00769526 -0.0398806 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1913 1914 4.28744 -0.190456 -0.1246 -0.00523147 0.0884533 -0.132183 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1864 1914 -0.0875273 -3.18437 0.008422 0.0670764 -0.0098103 0.0340302 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1914 1915 4.26013 -0.293275 -0.118631 0.00162434 0.0840828 -0.0931572 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1865 1915 0.110046 -2.95598 -0.203223 0.0707307 0.0097679 -0.00974171 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1915 1916 4.29278 -0.211865 -0.419779 -0.00516219 0.0925443 -0.104693 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1866 1916 0.165809 -2.92397 -0.0639948 0.0704789 0.00142009 0.0184804 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1916 1917 4.43892 -0.212728 -0.157385 -0.00128075 0.0870124 -0.177047 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1867 1917 -0.25459 -2.94055 -0.067981 0.0766394 0.00910864 -0.0155151 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1917 1918 4.24089 -0.232276 -0.177805 -0.01324 0.0511016 -0.120929 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1868 1918 0.0744493 -3.18284 -0.0596563 0.0497036 -0.0110359 -0.0138372 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1918 1919 4.16527 -0.25614 -0.129577 -0.00676019 0.0739457 -0.0449676 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1869 1919 0.0474249 -3.14388 -0.120452 0.0523094 -0.000940022 0.0649863 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1919 1920 4.2376 -0.208001 -0.244516 0.0025855 0.0658397 -0.128578 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1870 1920 -0.131812 -2.99875 -0.0187358 0.0535419 -0.00572999 -0.0170683 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1920 1921 4.26588 -0.244314 -0.138584 0.0169447 0.0923461 -0.129302 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1871 1921 0.172469 -3.1663 -0.203053 0.057713 0.00698398 -0.00323928 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1921 1922 4.29202 -0.326796 -0.249091 0.00999889 0.0881306 -0.0893554 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1872 1922 -0.100465 -3.18693 -0.118614 0.0761284 0.0021087 -0.0232732 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1922 1923 4.17805 -0.216368 -0.262239 -0.0106656 0.0997709 -0.046544 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1873 1923 -0.0256783 -3.09551 -0.206493 0.0508551 0.00287114 -0.0136379 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1923 1924 4.27869 -0.319575 -0.233288 -0.0235943 0.0785207 -0.0909385 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1874 1924 0.153733 -3.12105 -0.0643246 0.0435506 -0.00758778 -0.00679884 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1924 1925 4.29058 -0.376121 -0.384833 -0.00123667 0.0939581 -0.112237 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1875 1925 -0.0190031 -3.11941 -0.0322153 0.0538352 2.90802e-05 0.0887264 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1925 1926 4.39244 -0.23956 0.0539397 -0.01035 0.0845915 -0.127842 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1876 1926 0.0236955 -2.959 -0.096646 0.0505093 -0.0271878 0.000431228 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1926 1927 4.19606 -0.34414 -0.142735 -0.00773727 0.0841039 -0.0667369 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1877 1927 0.173492 -3.00229 -0.127557 0.0588094 -0.000669096 0.0608391 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1927 1928 4.30325 -0.266877 -0.14374 -0.0123015 0.0828402 -0.0535617 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1878 1928 -0.162028 -3.22612 -0.195156 0.0718848 -0.00182541 0.0323809 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1928 1929 4.19134 -0.324255 -0.178556 -0.0162972 0.0883525 -0.0796562 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1879 1929 -0.0358555 -3.01209 -0.053434 0.0657251 0.00166911 -0.0196347 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1929 1930 4.09887 -0.297373 -0.32448 0.00265376 0.0759434 -0.0684646 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1880 1930 0.157879 -3.04929 -0.0713773 0.0655567 0.00327823 0.0290589 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1930 1931 4.23549 -0.303304 -0.379125 0.00468234 0.0774373 -0.0812882 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1881 1931 0.0286061 -3.12105 0.0517603 0.0694921 -0.0056283 0.0145916 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1931 1932 4.08328 -0.391529 -0.19426 -0.0121089 0.0722206 -0.0945631 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1882 1932 -0.0399439 -2.92277 -0.0809829 0.0527822 -0.0069721 0.0710042 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1932 1933 4.06086 -0.167069 -0.0924443 -0.0182719 0.0867986 -0.0859814 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1883 1933 -0.052735 -2.93029 -0.147111 0.0653108 -0.00151232 0.00249172 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1933 1934 4.15542 -0.178941 -0.0754697 -0.0181083 0.0880364 -0.119904 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1884 1934 -0.0664556 -2.95549 -0.0643582 0.0736804 -0.0074965 -0.00673016 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1934 1935 4.28579 -0.482084 -0.197275 -0.000602183 0.0745662 -0.0762575 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1885 1935 -0.120315 -3.15726 -0.190176 0.0599016 0.00897308 -0.025345 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1935 1936 4.3514 -0.266014 -0.196074 -0.0118994 0.0771209 -0.0921799 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1886 1936 0.154242 -3.04692 -0.0974953 0.0547337 -0.000535011 0.0662167 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1936 1937 4.12983 -0.285903 -0.183014 0.0179957 0.0561641 -0.0796293 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1887 1937 -0.0863398 -3.22479 -0.161658 0.0534412 0.00288308 0.0673637 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1937 1938 4.21764 -0.27165 -0.0621017 -0.00391806 0.0844955 -0.142137 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1888 1938 -0.0734187 -3.02007 0.0673569 0.0676042 0.0134512 -0.0555018 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1938 1939 4.08981 -0.344466 -0.0921311 -0.0263845 0.0760042 -0.0575004 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1889 1939 0.0840464 -3.17894 -0.0339765 0.0519333 -0.0111514 0.0558327 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1939 1940 3.9116 -0.223302 -0.244041 -0.00472284 0.0642214 -0.0360385 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1890 1940 0.0570372 -2.8924 -0.0610536 0.0479607 -0.00817971 -0.0361353 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1940 1941 4.26428 -0.17288 -0.229269 0.00422024 0.103071 -0.115945 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1891 1941 0.131844 -3.0645 -0.232504 0.0791449 -0.00380398 0.0389546 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1941 1942 4.15675 -0.219201 -0.266267 -0.000560014 0.0727546 -0.135641 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1892 1942 0.0777617 -3.04831 -0.0535451 0.0631704 0.00942701 -0.0371857 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1942 1943 4.14824 -0.308997 -0.252387 -0.000623447 0.0904886 -0.0854588 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1893 1943 -0.128108 -2.88505 -0.155163 0.0588831 0.00675514 -0.0422598 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1943 1944 4.25728 -0.188387 -0.156685 -0.0101019 0.0732098 -0.112368 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1894 1944 0.153072 -3.01143 -0.0797814 0.0677367 -0.00878229 -0.007482 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1944 1945 4.02996 -0.35726 -0.0912853 0.00188491 0.0954209 -0.132888 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1895 1945 0.164682 -2.9473 -0.119452 0.0611001 -0.000673267 -0.0181416 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1945 1946 4.12195 -0.337303 -0.280472 -0.00303241 0.0869872 -0.0903253 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1896 1946 -0.023264 -3.04771 -0.152045 0.0619894 -0.00634507 0.0392784 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1946 1947 4.06167 -0.23868 -0.11998 0.00265271 0.0892516 -0.0327593 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1897 1947 0.00547007 -3.09013 -0.0511763 0.0619846 0.0226482 -0.0110786 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1947 1948 4.0425 -0.258 -0.250096 -0.0115353 0.0709673 -0.101372 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1898 1948 0.121128 -3.11473 -0.121931 0.0492621 0.0190299 -0.0223325 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1948 1949 3.97484 -0.296761 -0.193436 -0.0193701 0.0916655 -0.0781071 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1899 1949 0.151909 -2.89019 0.101183 0.0594345 -0.00383205 -0.0576626 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1949 1950 4.20071 -0.309989 -0.326205 0.00498975 0.0794809 -0.0219681 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1900 1950 -0.0558459 -3.05886 -0.00808693 0.0555724 -0.00178108 -0.00258199 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1950 1951 3.98914 -0.377714 -0.146508 -0.00503001 0.0779264 -0.0456139 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1901 1951 0.020223 -3.10738 -0.0417297 0.058371 -0.00154075 -0.00161483 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1951 1952 4.15649 -0.474466 -0.205463 0.013224 0.0776772 -0.149838 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1902 1952 -0.030244 -3.05845 -0.136567 0.073076 0.0222177 -0.0470917 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1952 1953 4.07392 -0.131107 -0.159059 -0.0101704 0.0816373 -0.020526 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1903 1953 0.0557011 -2.99479 -0.102065 0.0675648 -0.00381538 -0.0271069 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1953 1954 4.12942 -0.238501 -0.193384 -0.0172608 0.0778085 -0.0947855 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1904 1954 -0.216131 -3.03897 -0.0433695 0.0675301 0.0177496 -0.115951 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1954 1955 4.02161 -0.230868 -0.153143 -0.0050373 0.0722148 -0.164973 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1905 1955 -0.0897988 -2.97752 -0.10118 0.0403913 0.010461 0.0133102 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1955 1956 4.0127 -0.332368 -0.219003 -0.00789817 0.0838446 -0.0571936 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1906 1956 -0.14467 -3.05528 -0.312279 0.0916964 -0.00669889 -0.007295 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1956 1957 4.03161 -0.142439 -0.102149 -0.0106457 0.0602491 -0.0406136 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1907 1957 -0.00123278 -2.90526 -0.26953 0.0627806 -0.0049433 0.045618 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1957 1958 4.12457 -0.027463 -0.204845 -0.00720539 0.0870151 -0.0582056 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1908 1958 -0.0813435 -3.02588 -0.157532 0.0655548 -0.00357006 0.0378483 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1958 1959 4.1822 -0.196563 -0.382705 0.0133169 0.063573 -0.0505472 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1909 1959 -0.0978837 -2.90575 0.093453 0.0612773 -0.0101771 -0.0149189 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1959 1960 4.01098 -0.16293 -0.205224 0.000690703 0.0683197 -0.125481 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1910 1960 0.0592711 -3.1138 -0.247364 0.042871 0.0105628 0.0428797 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1960 1961 4.15577 -0.195198 -0.143934 -0.0131374 0.0808275 -0.0620354 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1911 1961 -0.150285 -2.98368 -0.165131 0.055658 0.0171125 -0.0177415 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1961 1962 4.09018 -0.436098 -0.185573 0.00168603 0.0734392 -0.0857874 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1912 1962 -0.0789751 -3.01499 -0.00610366 0.0720518 -0.0216005 -0.0843853 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1962 1963 4.23886 -0.278578 -0.0758427 -0.015394 0.0964312 -0.0925962 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1913 1963 -0.0355763 -3.07105 -0.0748421 0.065682 0.00753022 0.0274502 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1963 1964 3.98134 -0.180001 -0.190638 -0.0111859 0.0981133 -0.124912 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1914 1964 0.0190411 -2.94673 -0.0715748 0.0608257 0.00820011 -0.0121434 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1964 1965 4.0293 -0.29605 -0.192949 -0.0197484 0.0819707 -0.0836343 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1915 1965 -0.0626555 -2.99931 -0.241992 0.0651594 -0.0174585 0.0097151 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1965 1966 4.05788 -0.0722964 -0.149412 -0.0178659 0.0895746 -0.0876653 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1916 1966 -0.0834555 -3.04717 -0.145403 0.0560101 0.00345291 0.0225831 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1966 1967 4.0752 -0.299522 -0.203021 0.00613674 0.0771903 -0.0641583 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1917 1967 -0.0617324 -3.03557 -0.0924446 0.0617031 -0.00550161 0.0236195 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1967 1968 4.04603 -0.198135 -0.355313 -0.00646143 0.0831503 -0.0733695 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1918 1968 0.108933 -3.15224 -0.290402 0.0598904 0.0105879 -0.00255137 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1968 1969 3.97505 -0.193533 -0.0404268 0.000963879 0.0850782 -0.0726859 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1919 1969 -0.113101 -3.01724 -0.00961383 0.0669725 0.00283789 -0.0347312 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1969 1970 3.85677 -0.19319 -0.0938565 -0.0142197 0.083613 -0.0351686 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1920 1970 -0.197512 -3.11572 -0.157018 0.0708744 -0.00664834 0.0273647 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1970 1971 3.93538 -0.192721 -0.100265 -0.00327336 0.0778942 -0.0921695 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1921 1971 -0.179218 -3.18095 -0.0896117 0.0861331 -0.000132903 0.081152 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1971 1972 3.87697 -0.23189 -0.142868 -0.00194415 0.0649033 -0.0405224 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1922 1972 -0.0476279 -3.02727 -0.0677929 0.0620293 0.0183332 -0.0468609 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1972 1973 3.93295 -0.351428 -0.0692229 0.00157272 0.0777122 -0.0645434 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1923 1973 -0.18019 -3.1274 -0.215239 0.0605612 -0.000547583 -0.0478365 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1973 1974 4.08117 -0.325844 -0.143426 0.011943 0.0773388 -0.0861566 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1924 1974 0.0718273 -3.10457 -0.177574 0.0561563 0.00150109 -0.0534509 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1974 1975 3.96931 -0.200514 -0.227838 -0.0135039 0.0838421 -0.0910143 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1925 1975 -0.0852625 -2.9934 0.0333761 0.0691608 -0.000100165 0.0396848 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1975 1976 3.95499 -0.126193 -0.182623 0.0101559 0.0757382 -0.0414272 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1926 1976 -0.0549844 -2.95415 0.0503509 0.074622 0.00286758 -0.0197989 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1976 1977 3.93775 -0.105977 -0.299612 0.00251116 0.0748473 -0.0919241 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1927 1977 0.0499105 -3.05122 -0.122024 0.0615881 0.0182797 0.00690448 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1977 1978 3.9011 -0.365612 -0.104658 -0.00881255 0.073347 -0.031555 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1928 1978 0.0773659 -3.07539 -0.0405432 0.0525861 0.000438271 -0.0102741 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1978 1979 4.11376 -0.298042 -0.179663 -0.00309183 0.0877969 -0.0708691 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1929 1979 0.107398 -3.25687 0.0176977 0.0494088 -0.0221734 0.00732095 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1979 1980 3.83187 -0.257301 -0.171019 -0.000184932 0.0918396 -0.251722 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1930 1980 -0.11863 -3.04041 -0.122991 0.0487717 0.0118078 -0.0144252 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1980 1981 3.88607 -0.285043 -0.264392 -0.00570068 0.0822052 -0.0919888 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1931 1981 0.0186651 -3.18181 -0.139696 0.0557855 0.00998612 -0.0106596 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1981 1982 3.92373 -0.232823 -0.117316 0.00108363 0.0721919 -0.112173 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1932 1982 -0.0241102 -2.99522 -0.167005 0.0753525 -0.0178488 -0.0100052 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1982 1983 3.89774 -0.399653 -0.203818 -0.00998694 0.0693313 -0.143321 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1933 1983 0.135014 -2.82967 -0.252255 0.0644094 0.00820984 0.052871 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1983 1984 3.7314 -0.326964 -0.249638 -0.00458387 0.0856673 -0.149648 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1934 1984 0.044808 -3.12939 -0.0859541 0.0857895 -0.0104472 -0.0701079 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1984 1985 3.89 -0.181903 -0.283264 -0.00275248 0.0796951 -0.146341 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1935 1985 0.0236924 -3.08302 -0.0928126 0.0673263 -0.00174586 -0.0534962 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1985 1986 3.83248 -0.409762 -0.239389 -0.0139169 0.0736887 -0.0531359 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1936 1986 -0.00505125 -3.11936 -0.122213 0.0690315 -0.00639175 0.0574055 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1986 1987 4.06696 -0.272481 -0.22723 0.0143956 0.0983608 -0.0790062 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1937 1987 0.0263322 -2.97505 -0.133867 0.0476881 -0.0104861 0.0182313 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1987 1988 3.94074 -0.166553 -0.203753 -0.00466307 0.095582 -0.143967 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1938 1988 0.0091196 -3.11688 -0.178431 0.0461039 0.00581804 0.00249168 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1988 1989 3.99065 -0.304642 -0.162138 -0.00807173 0.0894635 -0.000532056 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1939 1989 -0.00433661 -3.26607 0.0314002 0.0449051 0.00750661 -0.0135727 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1989 1990 3.71339 -0.218157 -0.0834343 -0.00850129 0.0599762 0.00411139 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1940 1990 -0.0190984 -3.22341 -0.0442282 0.0567095 0.014596 -0.0250566 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1990 1991 3.93 -0.204349 -0.129851 -0.000377474 0.0711486 -0.0579703 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1941 1991 0.0897336 -2.94896 -0.0238168 0.0333184 0.0052942 -0.0727295 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1991 1992 3.92079 -0.288127 -0.269137 -0.00950973 0.0779951 -0.0870242 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1942 1992 -0.107628 -3.15056 0.040788 0.0350415 0.00204729 0.0227784 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1992 1993 3.85097 -0.408908 -0.198446 -0.00653542 0.0911453 -0.160269 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1943 1993 0.0377913 -2.97537 -0.00858782 0.0473134 0.00133275 -0.00761058 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1993 1994 3.83342 -0.209282 -0.107311 -0.00523756 0.0760703 -0.129525 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1944 1994 -0.200275 -3.02643 -0.145734 0.0553561 0.0124984 0.0833295 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1994 1995 3.84574 -0.097062 -0.189343 -0.0141308 0.0815852 -0.189678 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1945 1995 0.0516165 -2.97591 -0.0560244 0.0752554 -0.0060587 -0.0421071 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1995 1996 3.80267 -0.249033 -0.0632055 -0.0248118 0.07084 -0.091551 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1946 1996 0.121357 -3.04053 -0.200719 0.0611263 -0.00402293 0.0575747 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1996 1997 4.05999 -0.348409 -0.0678961 0.00148827 0.0813297 -0.0731714 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1947 1997 -0.0308405 -3.04748 0.0571645 0.0523132 -0.00572717 0.0819391 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1997 1998 3.58636 -0.259717 -0.0849707 -0.00130152 0.0771543 -0.0938153 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1948 1998 0.0536134 -3.12658 -0.320196 0.0687956 0.0098049 0.0385344 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1998 1999 3.75228 -0.132566 -0.0826785 0.00855786 0.0810907 -0.0815025 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1949 1999 0.030286 -3.07141 -0.0710082 0.0662994 -0.0132673 -0.0325276 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1999 2000 3.7061 -0.277007 -0.229495 -0.00764001 0.0678636 -0.0723049 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1950 2000 0.0148607 -3.13423 -0.138566 0.0633798 -0.00206171 0.0100648 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2000 2001 3.94372 -0.364221 -0.182918 0.00645856 0.0502168 -0.103713 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1951 2001 0.0521878 -3.03471 0.0377428 0.0596219 -0.00708902 0.0657467 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2001 2002 3.76193 -0.355789 -0.222014 -0.00300618 0.0753516 -0.0479499 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1952 2002 0.0312852 -3.05352 -0.188157 0.0675008 0.0202726 -0.043469 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2002 2003 3.67902 -0.213382 -0.214829 0.00701115 0.0853371 -0.112833 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1953 2003 -0.138849 -3.01898 -0.0750788 0.0611615 -0.00905312 0.0224817 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2003 2004 3.91755 -0.164977 -0.10725 0.0131947 0.0648788 -0.0717277 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1954 2004 -0.00099052 -3.14651 -0.0146388 0.0769402 -0.0157311 -0.00425177 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2004 2005 3.77653 -0.391448 -0.0360583 -0.010608 0.0958135 -0.0435752 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1955 2005 0.0925024 -3.09935 -0.0978751 0.0809205 -0.00698252 0.0460514 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2005 2006 3.80116 -0.310168 -0.138617 -0.00192078 0.0832512 -0.0808566 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1956 2006 -0.194563 -3.01287 0.0205387 0.0600865 0.00446102 0.0305715 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2006 2007 3.73529 -0.459481 -0.231161 -0.00750538 0.0695369 -0.0437146 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1957 2007 0.105266 -2.96184 -0.111297 0.0575965 -0.00939636 0.0651021 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2007 2008 3.73511 -0.347834 -0.158496 -0.0096189 0.0724432 -0.0660995 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1958 2008 -0.108838 -2.9883 -0.0176286 0.0661488 0.0109523 -0.0218325 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2008 2009 3.80865 -0.0847682 0.0484325 -0.00860126 0.0841538 -0.0958081 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1959 2009 0.0198086 -2.87677 -0.0693471 0.0462626 0.0101029 -0.0620391 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2009 2010 3.64592 -0.348139 -0.205187 -0.0144 0.0734242 -0.0908535 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1960 2010 0.0620823 -2.86315 -0.146143 0.0516219 -0.0059276 0.0166504 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2010 2011 3.83458 -0.176115 -0.0552606 0.00770637 0.0693927 -0.100231 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1961 2011 -0.104128 -3.09505 -0.0121927 0.0663289 0.00195369 0.0209419 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2011 2012 3.76957 -0.220653 -0.136653 -0.0111087 0.0662607 -0.0385169 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1962 2012 -0.0382338 -3.00643 -0.0654127 0.0568282 -0.00939105 -0.0513172 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2012 2013 3.6968 -0.260408 -0.306459 0.00809763 0.0715436 -0.0774 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1963 2013 -0.103737 -3.12396 -0.270104 0.0610715 -0.016514 0.0787495 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2013 2014 3.57015 -0.217549 -0.237674 0.00505963 0.068742 -0.0933335 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1964 2014 -0.0410864 -3.12942 -0.121939 0.0671667 -0.0188968 0.023357 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2014 2015 3.69388 -0.331596 -0.0171443 0.0141729 0.0550964 -0.158971 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1965 2015 -0.00394692 -3.12284 -0.120259 0.0468607 -0.003365 -0.0812927 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2015 2016 3.75549 -0.324537 -0.270617 0.00843679 0.0762542 -0.109485 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1966 2016 0.035538 -3.01311 -0.167803 0.0735814 -0.0187464 0.0506743 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2016 2017 3.66044 -0.416423 -0.151793 -0.00953658 0.0575649 -0.0875991 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1967 2017 0.00160172 -3.00319 -0.289741 0.0381222 0.00950498 0.0147429 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2017 2018 3.77146 -0.2592 -0.0438973 0.00856138 0.0676355 -0.152065 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1968 2018 0.0183999 -2.92201 0.0329823 0.0560734 -0.00541229 0.0589358 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2018 2019 3.69838 -0.318102 0.0969819 -0.00353239 0.058472 -0.0906684 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1969 2019 0.0269479 -3.06412 -0.134239 0.041109 0.00631797 -0.0485567 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2019 2020 3.62488 -0.229052 -0.194989 -0.00431024 0.0724754 -0.0967823 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1970 2020 -0.000304255 -3.18856 -0.112986 0.0627602 0.0078902 0.0385972 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2020 2021 3.67628 -0.359818 -0.0531481 0.00291086 0.0821518 -0.0514497 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1971 2021 0.0243198 -2.98738 -0.23178 0.0793911 -0.00397448 0.0673275 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2021 2022 3.70208 -0.00211951 0.035242 0.00466816 0.0752083 -0.143919 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1972 2022 0.0411305 -2.97061 -0.0454571 0.0803237 -0.0024945 -0.0109802 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2022 2023 3.70533 -0.343122 -0.21916 -0.011092 0.062428 -0.064884 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1973 2023 0.110846 -3.00954 -0.0460256 0.0523123 -0.00651303 -0.0717703 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2023 2024 3.57595 -0.130087 -0.182328 -0.00763289 0.0828123 -0.0692883 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1974 2024 -0.0597523 -3.03427 -0.0776605 0.0415787 0.00119917 0.0597269 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2024 2025 3.63867 -0.362192 -0.232067 6.71021e-06 0.0872261 -0.0926256 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1975 2025 -0.0932133 -3.05779 -0.152591 0.0573443 -0.00508391 0.0396799 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2025 2026 3.51279 -0.292839 -0.289881 -0.0342383 0.061289 -0.11843 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1976 2026 0.00357393 -3.23914 -0.161052 0.068616 -0.00646015 0.052866 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2026 2027 3.70234 -0.387619 -0.269292 0.00404123 0.077507 -0.153865 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1977 2027 -0.180899 -3.16128 -0.147999 0.084729 0.00248696 0.0222292 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2027 2028 3.56233 -0.372679 -0.200957 -0.00550305 0.0669253 -0.0339962 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1978 2028 -0.13379 -3.24197 -0.172663 0.0556349 -0.00512141 -0.0460592 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2028 2029 3.49367 -0.276565 -0.111897 0.00872853 0.0698488 -0.0909876 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1979 2029 0.157572 -3.08483 -0.015791 0.0561958 0.00428978 -0.00142322 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2029 2030 3.55546 -0.347194 -0.147411 0.00792586 0.0812436 -0.0735982 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1980 2030 0.0558258 -3.01001 -0.158652 0.0705229 -0.0357807 0.0155148 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2030 2031 3.59624 -0.121327 -0.182388 -0.00717412 0.0676787 -0.140362 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1981 2031 0.0523394 -3.16742 -0.19736 0.0479983 0.00712977 0.0050826 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2031 2032 3.67612 -0.369524 -0.125767 -0.0154269 0.0631136 -0.133743 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1982 2032 -0.21673 -2.86464 -0.162463 0.0627936 0.00608695 -0.0030869 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2032 2033 3.55253 -0.266153 -0.0398371 0.00205329 0.0751987 -0.109453 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1983 2033 -0.144195 -3.13249 0.00132992 0.0703013 -0.00318527 0.00140536 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2033 2034 3.58934 -0.307994 -0.207852 0.00107559 0.0675295 -0.0862884 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1984 2034 -0.0670177 -2.888 0.237676 0.056287 -0.0128674 0.0711759 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2034 2035 3.60535 -0.133341 -0.248406 0.0114793 0.0632323 -0.0995834 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1985 2035 -0.0209647 -3.17551 -0.267033 0.0536729 0.0104624 0.031267 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2035 2036 3.66779 -0.178988 -0.130556 -0.00301086 0.0635599 -0.0946509 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1986 2036 -0.0238239 -2.8232 -0.0525839 0.0708069 -0.00836265 0.0468911 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2036 2037 3.57846 -0.118432 -0.179432 0.00629884 0.0835163 -0.100247 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1987 2037 -0.0504269 -3.11407 -0.185938 0.0526284 -0.00551218 -0.0259865 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2037 2038 3.52523 -0.244794 -0.0520923 -0.0198477 0.0611237 -0.127133 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1988 2038 -0.0189585 -3.07027 -0.0683004 0.0748082 -0.00908523 -0.0230099 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2038 2039 3.7194 -0.243581 -0.219514 -0.00127801 0.0899491 -0.118238 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1989 2039 0.0147197 -3.09238 -0.208605 0.056931 0.00255577 0.0326083 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2039 2040 3.43304 -0.130643 -0.142288 0.00439302 0.0684212 -0.05758 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1990 2040 0.032072 -3.24973 -0.0696703 0.0679527 0.0135707 0.0290668 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2040 2041 3.4791 -0.198703 -0.126062 0.0121599 0.0839251 -0.138899 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1991 2041 -0.0359589 -3.21296 -0.0623838 0.0742012 0.0253433 -0.0125126 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2041 2042 3.64315 -0.226554 -0.315696 0.00271988 0.0742986 -0.151842 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1992 2042 -0.0774013 -3.063 -0.0814995 0.0774075 0.00164421 0.0314242 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2042 2043 3.50459 -0.266466 -0.173174 -0.0162543 0.0742343 -0.0756713 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1993 2043 -0.0160024 -2.94983 0.0273565 0.0683551 -0.0176981 0.0241458 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2043 2044 3.5959 -0.1959 -0.181279 -0.0141972 0.060515 -0.0838814 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1994 2044 0.0384637 -3.16603 -0.0156016 0.0636765 -0.0178174 0.0431538 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2044 2045 3.55489 -0.303045 -0.0642663 0.00604594 0.0725077 -0.0732478 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1995 2045 0.010927 -3.03111 0.0104183 0.0546198 0.000893637 0.0111643 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2045 2046 3.57822 -0.142312 0.105578 0.00886738 0.0837704 -0.130746 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1996 2046 0.097244 -2.99099 0.048626 0.0500272 -6.90939e-05 0.0213143 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2046 2047 3.42728 -0.356409 -0.161725 0.0110012 0.0698618 -0.0957525 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1997 2047 -0.0624482 -3.01433 -0.0802096 0.0718351 0.000960346 -0.00992014 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2047 2048 3.55289 -0.156051 -0.331846 0.0071787 0.067836 -0.072484 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1998 2048 -0.00224381 -3.00439 0.0464199 0.0498342 -0.011921 -0.000426229 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2048 2049 3.55217 -0.271874 -0.0598408 0.0101431 0.0856169 -0.089823 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1999 2049 -0.0144345 -3.06316 -0.175608 0.0514101 -0.00300242 -0.00371854 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2049 2050 3.60147 -0.114269 0.0564121 -0.00201539 0.0626433 -0.0877492 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2000 2050 -0.0643962 -3.18008 -0.166869 0.0550361 0.00769411 -0.0584173 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2050 2051 3.57746 -0.0468281 -0.0789584 -0.00395663 0.0705354 -0.157622 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2001 2051 0.0371151 -3.14533 -0.0838149 0.0651258 0.00222369 -0.0292995 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2051 2052 3.63038 -0.270854 -0.0144253 -0.00874243 0.0625857 -0.0683319 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2002 2052 0.0835603 -3.07361 -0.0633718 0.0528567 -0.000765593 -0.0420744 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2052 2053 3.31559 -0.181155 -0.304759 0.00772557 0.077911 -0.0912202 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2003 2053 0.115243 -3.09724 -0.138628 0.0673004 -0.00177217 -0.000381095 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2053 2054 3.30556 -0.217723 -0.168323 -0.00390401 0.0572114 -0.0469201 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2004 2054 -0.0706894 -3.09164 0.00896299 0.0608617 0.0206609 0.0190265 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2054 2055 3.58314 -0.265036 0.0422537 0.0208767 0.0656358 -0.0571548 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2005 2055 -0.0874422 -3.10329 -0.0692837 0.058226 -0.012659 -0.0150131 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2055 2056 3.48936 -0.432252 -0.0716867 -0.013267 0.0675975 -0.128845 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2006 2056 -0.0634775 -2.90446 0.0393535 0.0932889 -0.0030456 0.057481 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2056 2057 3.36455 -0.26077 -0.096088 0.00434994 0.0675728 -0.140037 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2007 2057 -0.00118421 -3.20395 -0.0703197 0.0534714 0.0168948 0.03099 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2057 2058 3.59821 -0.233977 0.0142636 -0.0033452 0.039423 -0.115332 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2008 2058 0.089576 -3.17679 -0.0790087 0.0410658 -0.000153665 -0.0114374 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2058 2059 3.57646 -0.124742 0.00405078 -0.00884704 0.0842831 -0.10149 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2009 2059 0.154141 -3.27799 -0.190217 0.0696598 0.000463073 -0.00592491 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2059 2060 3.42214 -0.19946 -0.141362 0.0143252 0.0747396 -0.181241 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2010 2060 0.0586031 -3.08102 -0.193086 0.0573666 -0.00436353 0.00348661 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2060 2061 3.3802 -0.21902 -0.0964095 -0.0120444 0.0632004 -0.0349306 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2011 2061 -0.0205971 -2.98712 -0.255829 0.0667232 -0.0128329 -0.0306593 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2061 2062 3.48935 -0.332609 -0.0179532 0.00416518 0.0673758 -0.109937 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2012 2062 0.0452902 -2.97497 -0.245561 0.0504328 0.00205029 0.0135809 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2062 2063 3.70822 -0.389152 -0.0994019 -0.0108951 0.0681705 -0.130221 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2013 2063 -0.00247814 -3.00499 -0.19276 0.0671112 0.00306903 0.0167438 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2063 2064 3.39377 -0.307898 -0.0105911 0.000943008 0.0661764 -0.166664 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2014 2064 0.123495 -3.09005 -0.223313 0.0691352 0.00565192 0.0205554 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2064 2065 3.32351 -0.306747 -0.247074 0.0154149 0.073912 -0.0140332 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2015 2065 -0.00684393 -3.1065 0.0218204 0.053722 -0.00422538 0.0804196 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2065 2066 3.37625 -0.265736 -0.0512975 -0.00918942 0.0594238 -0.142239 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2016 2066 0.00874849 -2.94551 -0.0028244 0.0602759 -0.0214517 -0.0407197 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2066 2067 3.34244 -0.109624 -0.375367 0.0222302 0.0717789 -0.115241 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2017 2067 0.0724536 -3.15653 -0.241265 0.0772802 0.000322605 -0.0134154 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2067 2068 3.36437 -0.170279 -0.144049 -0.00182204 0.0616702 -0.0830319 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2018 2068 -0.146806 -3.01057 -0.121051 0.0515932 0.012459 -0.00615419 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2068 2069 3.34494 -0.302038 -0.0238283 -0.0074607 0.0591736 -0.0889325 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2019 2069 -0.0806291 -2.9969 -0.0175986 0.0547411 -0.00986048 0.0349053 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2069 2070 3.32125 -0.365839 -0.170927 -0.0108813 0.0614188 -0.101943 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2020 2070 0.186252 -3.24149 -0.179033 0.0711406 0.00587537 0.0598512 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2070 2071 3.34935 0.0302785 -0.221548 -0.00861538 0.0809865 -0.0684725 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2021 2071 -0.0481338 -3.13361 -0.101039 0.0601677 -0.0165501 -0.0205402 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2071 2072 3.31189 -0.293413 -0.27597 -0.00268784 0.0785462 -0.06368 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2022 2072 0.112971 -3.1146 -0.0905336 0.0517298 0.00109921 -0.00731545 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2072 2073 3.39301 -0.200953 -0.192076 -0.00107057 0.0730957 -0.0756835 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2023 2073 0.0200438 -3.02608 -0.0331133 0.034852 0.00584668 0.0748838 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2073 2074 3.2355 -0.281565 -0.28037 0.00725043 0.066245 -0.0864896 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2024 2074 -0.0596035 -3.19203 0.00444458 0.0586624 0.00533366 -0.00247801 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2074 2075 3.34897 -0.243918 -0.380994 0.00719646 0.0703908 -0.080131 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2025 2075 -0.154515 -3.15247 -0.0985383 0.0646652 0.00503656 -0.0110783 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2075 2076 3.09958 -0.245393 0.0389515 -0.00125908 0.0733213 -0.074256 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2026 2076 0.00105436 -3.13418 -0.189395 0.0640034 -0.00734671 0.0561624 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2076 2077 3.18686 -0.0629364 -0.322865 0.00663695 0.0853561 -0.133736 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2027 2077 0.11636 -3.03798 -0.0808031 0.0721439 -0.00156617 0.00876136 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2077 2078 3.27248 -0.0802403 -0.169341 -0.00577254 0.0860289 -0.0914254 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2028 2078 -0.0823317 -2.97797 -0.0764544 0.0692111 -0.0153935 -0.0512033 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2078 2079 3.36367 -0.398205 -0.153276 -0.00617412 0.0667595 -0.0888232 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2029 2079 -0.083409 -3.16984 -0.117541 0.059723 -0.00340749 -0.031345 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2079 2080 3.33689 -0.167474 -0.173329 -0.0182651 0.0682695 -0.0790131 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2030 2080 -0.026439 -3.08984 -0.168958 0.0668361 0.00477201 0.00599049 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2080 2081 3.29572 -0.356409 -0.0220755 -0.0126983 0.0683333 -0.0727979 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2031 2081 -0.0878578 -3.23564 -0.0802511 0.055439 0.00558155 0.0158114 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2081 2082 3.10932 -0.101866 -0.187508 0.00567295 0.0586972 -0.104557 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2032 2082 0.16457 -3.02033 -0.00474537 0.0544923 0.00328378 -0.0386924 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2082 2083 3.385 -0.228971 0.0418952 -0.000446854 0.0551066 -0.100299 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2033 2083 0.096681 -3.17533 -0.179596 0.052828 -0.00682934 -0.0114303 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2083 2084 3.1837 -0.327535 -0.147419 0.000648578 0.0686683 -0.0733417 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2034 2084 -0.0175213 -3.17233 -0.355849 0.0597391 -0.00164909 0.0204688 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2084 2085 3.33913 -0.3002 -0.0953406 0.00583069 0.0644125 -0.0888377 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2035 2085 -0.00208623 -3.05323 -0.113959 0.0829344 0.00757171 0.0242746 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2085 2086 3.29366 -0.112846 -0.182767 0.00129288 0.0851211 -0.146947 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2036 2086 -0.201835 -2.89584 -0.104823 0.0503072 -0.0130249 -0.0347829 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2086 2087 3.26502 -0.225465 -0.133874 -0.00978673 0.0710281 -0.159176 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2037 2087 -0.0342074 -3.03427 -0.0389665 0.071919 -0.00548747 0.0203872 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2087 2088 3.31718 -0.467704 -0.249224 0.00665724 0.0688026 -0.16404 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2038 2088 -0.0874539 -3.00212 -0.127525 0.0553764 0.00434 0.00207149 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2088 2089 3.36706 -0.255742 -0.186457 -0.0210302 0.0651889 -0.0649077 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2039 2089 -0.105224 -2.97762 -0.249731 0.0902369 -0.0123383 -0.00576199 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2089 2090 3.29221 -0.213925 -0.221204 -0.0102906 0.0631515 -0.140249 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2040 2090 0.0733136 -2.91418 -0.0160392 0.061554 0.00148906 0.0453055 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2090 2091 3.14634 -0.287549 -0.0415104 -0.00920953 0.0476644 -0.0834088 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2041 2091 0.00508262 -2.97265 -0.0364925 0.061254 0.000248604 -0.00907404 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2091 2092 3.4355 -0.164266 -0.241845 -0.00673108 0.067254 -0.0811744 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2042 2092 0.0856552 -2.91678 -0.286219 0.0425361 0.00794308 0.036011 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2092 2093 3.15122 -0.262831 -0.209649 -0.00120014 0.0441063 -0.16746 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2043 2093 0.173001 -3.01187 -0.172236 0.0702964 -0.0343912 -0.019426 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2093 2094 3.23982 -0.0802858 0.00519565 -3.38582e-05 0.0690729 -0.149072 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2044 2094 -0.170521 -3.00903 0.0820987 0.0656561 0.00435668 0.0151329 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2094 2095 3.41168 -0.298765 -0.0959007 0.00154137 0.0716667 -0.0830857 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2045 2095 -0.0344129 -3.17738 -0.210418 0.0750575 -0.00504989 0.00342019 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2095 2096 3.19036 -0.336984 -0.0754017 0.00254432 0.0737186 -0.106548 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2046 2096 0.0357437 -2.97089 -0.172259 0.037961 0.00975672 0.0566529 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2096 2097 2.9825 -0.240019 -0.230277 -0.00926356 0.0664646 -0.107576 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2047 2097 -0.179329 -3.05595 -0.199372 0.0557119 -0.000276223 -0.0091321 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2097 2098 3.24548 -0.418819 -0.0919402 -0.0131551 0.0558481 -0.0254452 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2048 2098 0.0239904 -3.14064 -0.0721547 0.0628278 0.00357536 -0.00128961 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2098 2099 3.16442 -0.257845 -0.351951 -0.00100272 0.0286973 -0.157252 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2049 2099 0.0447434 -3.06865 -0.206976 0.0413987 0.00110092 0.0353858 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2099 2100 3.13503 -0.170765 -0.0585885 -0.0058766 0.0680699 -0.112874 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2050 2100 -0.123194 -2.78671 -0.255897 0.0778827 0.000634355 0.00619237 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2100 2101 3.11874 -0.201613 -0.165434 0.00720114 0.0736508 -0.153177 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2051 2101 0.0189238 -3.13952 -0.119553 0.0576161 -0.0200777 -0.00339139 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2101 2102 3.21948 -0.242775 -0.154584 -0.0106284 0.0709991 -0.158461 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2052 2102 -0.154336 -3.15101 0.00879614 0.0734826 0.0194796 -0.00151207 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2102 2103 3.08549 -0.199584 -0.183659 -0.00910293 0.0642013 -0.12979 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2053 2103 0.0214168 -3.01003 0.0169212 0.0589921 0.0110367 -0.0233899 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2103 2104 3.24132 -0.241215 -0.292536 0.00196296 0.0582606 -0.13969 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2054 2104 0.0983086 -3.02869 -0.0370127 0.0703845 0.00778315 0.0168976 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2104 2105 3.12134 -0.301012 -0.098041 0.0123789 0.058101 -0.0867257 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2055 2105 0.185214 -3.3471 0.0350969 0.0619295 -0.00332093 0.0150214 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2105 2106 3.19036 -0.30163 -0.207732 -0.00107278 0.070542 -0.116465 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2056 2106 -0.0120497 -3.04035 -0.225792 0.0558352 -0.0126199 -0.0729789 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2106 2107 3.11121 -0.241309 0.0191096 -0.0177954 0.0594074 -0.122914 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2057 2107 -0.149921 -2.95745 -0.165196 0.0742485 0.00929994 0.0654027 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2107 2108 3.07783 -0.278546 -0.123676 -0.00834733 0.061173 -0.209048 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2058 2108 0.000495389 -2.98658 -0.0119766 0.0539133 -0.00398004 0.0116258 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2108 2109 3.16526 -0.0937671 -0.16787 -0.0022322 0.0714973 -0.110275 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2059 2109 -0.0916159 -2.94045 -0.216918 0.0693527 0.00724444 -0.029856 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2109 2110 3.00497 -0.303564 -0.00339931 -0.000248477 0.0629414 -0.123826 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2060 2110 -0.0533854 -2.85278 0.00704746 0.0612155 0.000502768 0.065519 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2110 2111 3.15378 -0.297936 -0.0224724 -0.00205779 0.0556431 -0.0875043 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2061 2111 -0.146266 -3.00686 -0.215619 0.0446226 -0.0209561 -0.0216762 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2111 2112 3.16663 -0.0369884 -0.0054611 -0.0107492 0.055226 -0.0712642 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2062 2112 -0.129272 -3.03663 -0.115804 0.0497388 -0.00357638 -0.0324303 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2112 2113 3.0169 -0.117958 -0.0508984 -0.00933431 0.0736519 -0.133225 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2063 2113 -0.130455 -2.92247 -0.0128724 0.03888 -0.00499482 -0.00382037 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2113 2114 3.18669 -0.224334 -0.153768 0.00498151 0.0631218 -0.0530628 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2064 2114 0.261451 -3.10266 -0.0498864 0.0530091 -0.00785628 0.0562943 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2114 2115 2.91763 -0.188078 -0.206345 -0.000672828 0.0722523 -0.0837345 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2065 2115 0.0254718 -3.00189 0.0231042 0.0657407 0.0137097 0.00990657 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2115 2116 3.14354 0.00118941 -0.1014 -0.00331625 0.0706252 -0.138874 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2066 2116 -0.049218 -3.13552 0.0189291 0.0516224 0.00153337 0.00243076 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2116 2117 2.96317 -0.239017 -0.116822 0.0136974 0.0716234 -0.0977087 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2067 2117 -0.107908 -2.88364 0.0978589 0.0653825 0.0102611 0.00733026 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2117 2118 3.13744 -0.0938027 0.103234 0.0235355 0.057976 -0.0923654 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2068 2118 0.0766294 -3.06592 -0.154883 0.0615836 0.00299977 0.0851522 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2118 2119 3.08753 -0.21266 0.050822 -0.00288516 0.0641923 -0.0580081 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2069 2119 -0.18226 -2.96298 -0.220603 0.0599494 0.0130247 0.00427652 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2119 2120 2.90142 -0.20835 -0.214941 -0.0156517 0.0556673 -0.103197 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2070 2120 0.133802 -2.89555 -0.130823 0.0609887 0.0176603 -0.0365241 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2120 2121 2.94659 -0.185591 -0.298557 -0.0052582 0.0430418 -0.0805965 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2071 2121 0.0431569 -3.14066 -0.147187 0.0733879 0.0283546 0.0276001 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2121 2122 3.05456 -0.147706 -0.163355 0.00895099 0.0441724 -0.0932113 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2072 2122 0.0265842 -3.16831 0.00734246 0.0393853 -0.0204875 -0.0333689 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2122 2123 2.86447 -0.186523 -0.103665 0.00509991 0.0415548 -0.109404 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2073 2123 0.000393012 -2.99798 0.0855685 0.0507149 0.00252677 -0.0717992 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2123 2124 3.04689 -0.297491 -0.102629 0.00439869 0.0605626 -0.171355 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2074 2124 -0.0254687 -3.02397 -0.20654 0.0672056 -0.0136651 0.0418254 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2124 2125 3.08765 -0.250439 -0.0506802 0.0141969 0.0395219 -0.134943 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2075 2125 -0.0102956 -3.03346 -0.0513876 0.0696785 -0.00988992 0.0195109 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2125 2126 3.02846 -0.27499 -0.229663 -0.00414909 0.0498197 -0.0153707 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2076 2126 0.0476452 -3.0611 -0.282201 0.0627264 0.0163537 -0.0171143 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2126 2127 2.94135 -0.331537 -0.163876 -0.00184658 0.0718784 -0.0532898 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2077 2127 -0.0510679 -2.99195 -0.320886 0.0562834 -0.00924539 -0.0591864 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2127 2128 2.99822 -0.316052 -0.0903634 0.00932171 0.0470029 -0.0352046 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2078 2128 0.01914 -3.14313 -0.0788628 0.0486667 -0.0109594 -0.0232551 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2128 2129 3.09378 -0.059808 -0.0984537 -0.0189384 0.0712385 -0.177982 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2079 2129 0.0908892 -2.9919 -0.0835521 0.082241 0.00911466 -0.0573359 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2129 2130 3.06748 -0.19482 -0.204036 0.0021858 0.0550733 -0.0808815 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2080 2130 -0.0279914 -2.86856 -0.011704 0.0596608 -0.0120681 0.0510995 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2130 2131 2.88483 -0.267356 -0.0967774 -0.0166276 0.0726537 -0.0762725 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2081 2131 -0.041066 -3.00748 -0.119344 0.05635 0.020397 -0.0285808 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2131 2132 3.02909 -0.170109 -0.18227 0.00293366 0.0645805 -0.162191 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2082 2132 -0.114778 -3.13531 -0.0993181 0.0461516 0.0322137 0.0441368 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2132 2133 2.86662 -0.358957 -0.152816 -0.0185076 0.054713 -0.0922482 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2083 2133 -0.0300311 -3.04495 -0.170569 0.0654075 0.00777198 -0.0401034 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2133 2134 3.03495 -0.282425 0.129501 0.00286561 0.0330925 -0.128469 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2084 2134 -0.233249 -2.98449 -0.139945 0.0551031 0.00284808 -0.0435305 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2134 2135 3.03235 -0.337068 -0.0352917 0.00162051 0.0640574 -0.0525518 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2085 2135 -0.156357 -3.00282 -0.00552253 0.068278 -0.0036317 0.00547228 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2135 2136 2.99134 -0.374864 -0.0640829 -0.00024072 0.0571269 -0.207926 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2086 2136 -0.0496582 -3.02762 -0.129938 0.0448528 -0.00354146 0.0879703 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2136 2137 2.85107 -0.177509 0.0270334 -0.00417102 0.0542517 -0.0881676 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2087 2137 -0.161622 -2.94154 -0.0194867 0.0385729 0.0203393 -0.0163314 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2137 2138 2.705 -0.398588 -0.0867881 0.00757544 0.0525705 -0.0912204 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2088 2138 -0.120914 -3.04911 -0.0946241 0.046067 -0.0102888 -0.0102718 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2138 2139 3.02087 -0.144757 -0.00298317 -0.0228381 0.0736392 -0.103116 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2089 2139 -0.19102 -3.08136 -0.0237986 0.0502337 -0.00177006 0.0296535 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2139 2140 3.01131 -0.236663 -0.092828 -0.010391 0.0520876 -0.170082 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2090 2140 -0.170683 -2.81957 -0.262863 0.0746683 -0.0113907 0.00428683 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2140 2141 2.85416 -0.214898 -0.0965311 -0.0178113 0.0680416 -0.183037 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2091 2141 0.0408146 -3.10091 -0.0220481 0.0613321 0.00395719 0.0189992 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2141 2142 2.96134 -0.228075 -0.0354297 -0.00785753 0.0455761 -0.0920851 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2092 2142 0.254939 -3.03945 -0.131421 0.0670357 0.00511291 -0.0629439 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2142 2143 2.93735 -0.211107 -0.0533829 -0.0156941 0.0580065 -0.104052 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2093 2143 -0.0833379 -2.95533 -0.121737 0.0691359 -0.00096858 -0.0205342 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2143 2144 2.94033 -0.239342 -0.134921 0.00366534 0.0535404 -0.125346 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2094 2144 -0.119895 -3.15628 -0.11941 0.0622629 -0.0136203 -0.00387472 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2144 2145 2.82771 -0.058074 -0.0847544 -0.0042735 0.0771758 -0.0987404 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2095 2145 -0.060066 -2.89078 -0.266169 0.0654683 0.00039393 -0.0272923 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2145 2146 2.81758 -0.241485 -0.0455579 -0.00589462 0.0769249 -0.0817759 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2096 2146 0.010105 -3.07861 -0.066546 0.0756127 -0.00710492 -0.0659996 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2146 2147 2.74998 -0.415505 0.0589001 -0.0137554 0.0399766 -0.120529 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2097 2147 -0.0671575 -2.98555 -0.223243 0.0580397 0.0148279 -0.0150881 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2147 2148 2.83017 -0.13845 -0.0723086 -0.00633034 0.0619657 -0.121942 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2098 2148 -0.102852 -2.91569 0.0028844 0.0707376 -0.0144605 -0.0463225 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2148 2149 2.8416 -0.184699 -0.0206475 0.00337293 0.0616063 -0.13522 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2099 2149 0.0340349 -3.19928 -0.0715693 0.0512431 0.00256486 0.0101582 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2149 2150 2.76972 0.0193745 -0.116096 -0.00344632 0.0604719 -0.148043 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2100 2150 0.0117521 -3.04309 -0.0911104 0.0620405 -0.00906356 -0.00620278 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2150 2151 2.79106 -0.395836 -0.144435 0.0124217 0.0506971 -0.160353 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2101 2151 0.00970708 -3.14109 -0.297364 0.0557185 0.00686157 -0.00236174 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2151 2152 3.00288 -0.14102 0.0517604 0.0053679 0.06271 -0.0743961 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2102 2152 -0.0120343 -3.21792 -0.191891 0.070351 -0.00573214 -0.0445803 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2152 2153 2.80302 -0.297836 -0.17321 -0.0107993 0.0346496 -0.139972 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2103 2153 -0.0482759 -3.12102 -0.127425 0.077672 -0.00428909 -0.012069 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2153 2154 2.90242 -0.325618 -0.140133 0.000624627 0.0542871 -0.103751 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2104 2154 -0.0249924 -2.95525 -0.0808759 0.0642462 0.0213524 0.029783 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2154 2155 2.82276 -0.191489 -0.172371 -0.00978901 0.0584721 -0.0786566 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2105 2155 -0.0253103 -3.07117 -0.0849674 0.0576022 0.016439 -0.0312684 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2155 2156 2.67414 -0.152866 -0.173903 -0.0185616 0.0413402 -0.174089 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2106 2156 -0.00699182 -2.92859 -0.128395 0.060665 0.00447888 -0.026431 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2156 2157 2.82588 -0.271739 -0.046187 -0.000265027 0.0526901 -0.0930627 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2107 2157 -0.0170204 -3.20539 -0.0960487 0.0570777 -0.00442251 -0.0200596 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2157 2158 2.74048 -0.220883 -0.228373 0.00905551 0.0534038 -0.076724 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2108 2158 0.204426 -3.10931 -0.0617148 0.0596847 0.0153916 0.035025 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2158 2159 2.63973 -0.0802336 -0.190278 -0.00792756 0.0552939 -0.14816 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2109 2159 -0.150567 -3.05978 -0.0651103 0.0623285 -0.00902001 -0.0463878 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2159 2160 2.76106 -0.346252 -0.116985 -0.0207811 0.0286117 -0.0364182 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2110 2160 0.256321 -2.90869 -0.231602 0.0697025 -0.0111693 0.0570987 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2160 2161 2.62533 -0.340821 -0.0992983 -0.0148021 0.0619839 -0.074371 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2111 2161 0.145595 -3.06737 -0.100928 0.0610828 0.0118919 0.030932 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2161 2162 2.6436 -0.257744 -0.0761311 -0.00198371 0.0644577 -0.138977 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2112 2162 -0.102644 -3.04447 -0.132148 0.0698521 -0.00310548 0.0316294 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2162 2163 2.77023 -0.410161 -0.124668 -0.0167919 0.0616824 -0.12956 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2113 2163 0.0106771 -2.97068 0.0332433 0.0643192 0.00212709 0.0603782 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2163 2164 2.58488 -0.278603 0.0174039 -0.00925431 0.0550927 -0.122031 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2114 2164 0.153236 -3.11544 -0.0336354 0.0566081 0.00905873 -0.0189256 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2164 2165 2.60739 -0.257122 -0.101955 -0.0153533 0.0667349 -0.0966007 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2115 2165 -0.000287043 -2.98676 -0.147097 0.0661296 0.000172252 -0.026388 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2165 2166 2.68056 -0.273622 0.0528448 0.00204809 0.0458905 -0.109995 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2116 2166 0.00458294 -3.0702 -0.00728502 0.0524605 0.00948238 0.012112 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2166 2167 2.81107 -0.156203 0.0491687 -0.0133144 0.06158 -0.0379959 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2117 2167 0.061471 -3.15293 -0.0660774 0.0490614 -0.00338492 -0.00657597 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2167 2168 2.76063 -0.105588 0.0212139 -0.0032577 0.0438386 -0.133228 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2118 2168 0.159012 -2.93752 -0.26102 0.0675307 -0.00191728 -0.0303468 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2168 2169 2.60847 -0.34208 -0.191335 0.0123268 0.056977 -0.10391 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2119 2169 0.193779 -2.95555 0.00395872 0.0547442 -0.0137967 -0.0126171 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2169 2170 2.69378 -0.243534 0.0365211 0.00629527 0.0484134 -0.139026 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2120 2170 -0.0198997 -3.20647 -0.0217357 0.0427429 -0.00325094 -0.00539372 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2170 2171 2.56223 -0.091304 0.0936846 0.00299023 0.0364252 -0.127767 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2121 2171 -0.139601 -3.16729 -0.106272 0.0530322 -0.00561885 0.0544867 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2171 2172 2.62996 -0.251588 -0.126104 0.00710187 0.0535995 -0.102385 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2122 2172 0.00951113 -3.08614 -0.0493098 0.0679428 -0.0168607 0.0182804 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2172 2173 2.57139 -0.170799 -0.0875925 -0.0104156 0.0589215 -0.134291 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2123 2173 0.132089 -2.95522 -0.112685 0.0728768 0.00457346 -0.0239531 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2173 2174 2.78383 -0.163845 -0.171656 0.00336818 0.0477432 -0.118073 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2124 2174 0.118418 -3.04213 -0.0818185 0.0847543 0.00257283 -0.0134623 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2174 2175 2.56906 -0.20738 -0.138053 -0.0141802 0.0657524 -0.106051 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2125 2175 0.0139486 -3.06089 -0.0375995 0.0535071 0.00688034 -0.0275647 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2175 2176 2.58835 -0.1435 -0.203424 -0.0220256 0.0553011 -0.108426 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2126 2176 -0.113293 -3.0193 -0.0628315 0.05858 -0.0160686 -0.011798 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2176 2177 2.78201 -0.0757288 -0.0590521 -0.00296881 0.0606651 -0.132334 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2127 2177 0.0950199 -2.96638 -0.0580626 0.0415916 0.0109129 0.0825153 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2177 2178 2.71021 -0.280013 -0.0592529 -0.0156621 0.0437127 -0.0595227 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2128 2178 0.0648743 -2.75039 0.13961 0.0549993 0.00896194 0.0342155 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2178 2179 2.55366 -0.245601 -0.0176089 0.00949529 0.0633613 -0.0300987 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2129 2179 -0.0135544 -3.02566 -0.00291222 0.0584907 -0.000769573 0.0605119 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2179 2180 2.5375 -0.322054 -0.168304 -0.020573 0.0660738 -0.174695 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2130 2180 0.105597 -3.10984 -0.105639 0.0802704 0.00551807 -0.0450681 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2180 2181 2.63204 -0.139707 -0.0836986 -0.00338655 0.0454505 -0.108587 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2131 2181 0.154913 -2.81921 -0.0794897 0.0642984 0.00329247 0.0504714 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2181 2182 2.60929 -0.226707 -0.0366647 -0.00813421 0.0507866 -0.121907 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2132 2182 0.0572089 -3.08445 0.0161857 0.0587952 -0.0215872 -0.0789391 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2182 2183 2.46535 -0.163446 -0.0820948 -0.0162908 0.0689026 -0.111217 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2133 2183 0.20885 -3.20112 -0.112124 0.057796 0.0055474 0.0132519 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2183 2184 2.60707 -0.173847 0.0184197 -0.0101192 0.0491608 -0.168649 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2134 2184 -0.00756476 -3.02709 -0.190457 0.0717803 -0.00256363 0.0368102 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2184 2185 2.63386 -0.098519 0.0738556 -0.00844361 0.0576049 -0.152592 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2135 2185 -0.192417 -3.10896 -0.0359544 0.0758008 0.0126583 -0.0141557 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2185 2186 2.58423 -0.145607 -0.0829623 -0.0233167 0.0647222 -0.0841058 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2136 2186 -0.0432472 -3.04974 0.0556173 0.0516961 0.00628261 0.0038474 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2186 2187 2.71082 -0.231633 -0.0952657 0.00573524 0.0407861 -0.147922 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2137 2187 0.192097 -3.03517 -0.228358 0.0532266 0.0241612 -0.0447211 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2187 2188 2.66462 -0.138512 0.0944016 -0.00179948 0.0434429 -0.081822 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2138 2188 -0.0177225 -3.05202 -0.22512 0.0532346 0.0243122 -0.034997 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2188 2189 2.40702 -0.191167 -0.0507019 0.00255912 0.0455441 -0.0822839 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2139 2189 -0.0492927 -3.15565 -0.0285129 0.0531856 0.00512708 -0.0118711 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2189 2190 2.58494 -0.380584 -0.098209 0.0154096 0.0479391 -0.134884 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2140 2190 0.101683 -2.87027 0.0241184 0.0657311 0.00920469 0.0086501 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2190 2191 2.56239 -0.261385 -0.0668467 0.00890474 0.0484508 -0.0991698 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2141 2191 -0.00193299 -3.18117 -0.137418 0.0585993 0.00424966 -0.00175326 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2191 2192 2.51927 -0.168366 -0.131046 0.0153068 0.0540741 -0.094574 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2142 2192 0.0371219 -3.0515 -0.103975 0.0596846 -0.0076224 0.00152479 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2192 2193 2.53748 -0.046566 -0.0662339 0.00909192 0.0621657 -0.139698 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2143 2193 0.115534 -3.02731 -0.110445 0.0789851 0.0084502 -0.067299 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2193 2194 2.46796 -0.0634905 0.0617769 -0.00334595 0.0511806 -0.140635 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2144 2194 0.0262407 -2.98219 -0.140879 0.0552686 -0.00751029 -0.070464 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2194 2195 2.55324 -0.21086 -0.0280942 0.00739696 0.0499895 -0.10125 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2145 2195 -0.0639281 -3.11846 -0.354936 0.071781 0.000760186 0.04394 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2195 2196 2.49325 -0.160726 -0.0387394 0.0114046 0.0482068 -0.0341091 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2146 2196 -0.0161992 -2.93174 -0.131956 0.062914 -0.00557051 -0.0191115 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2196 2197 2.74131 -0.235165 -0.181812 -0.0173927 0.0439551 -0.15011 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2147 2197 -0.0479604 -2.94527 0.0440888 0.0591484 -0.012885 0.0628588 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2197 2198 2.54727 -0.175575 -0.0673235 0.010302 0.0560763 -0.0422483 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2148 2198 0.0559343 -3.08769 -0.206948 0.0671437 0.0309344 0.0315174 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2198 2199 2.443 -0.192448 -0.197352 0.00137626 0.0315989 -0.111309 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2149 2199 -0.187 -2.95398 -0.113378 0.0758558 -0.000467136 0.0393832 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2199 2200 2.55334 -0.114688 0.105397 0.00297992 0.0416396 -0.137647 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2150 2200 0.0612344 -3.01045 -0.174001 0.042645 -0.00139287 0.11777 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2200 2201 2.53868 -0.156379 0.025403 0.00102383 0.0456967 -0.115938 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2151 2201 -0.0819293 -2.96053 -0.156127 0.0527369 -0.017202 -0.0607376 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2201 2202 2.31722 -0.198021 -0.104894 -0.00218198 0.0586299 -0.103799 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2152 2202 -0.171209 -3.11954 -0.167808 0.0430741 0.00181673 0.0545987 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2202 2203 2.3647 -0.198329 -0.124762 0.0230278 0.0479874 -0.109354 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2153 2203 -0.000337496 -2.99622 0.00581779 0.0357173 -0.0152898 -0.0439402 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2203 2204 2.56192 -0.239004 -0.0748405 0.00771442 0.0608531 -0.110621 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2154 2204 -0.168527 -3.13153 -0.145714 0.0523454 -0.00158164 -0.0442335 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2204 2205 2.48643 -0.155395 -0.0622614 -0.0144722 0.0484022 -0.154677 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2155 2205 -0.102031 -3.02013 -0.108693 0.0455811 0.0116463 0.00559224 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2205 2206 2.53363 -0.216545 -0.147638 -0.0111186 0.0477272 -0.0725542 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2156 2206 -0.0961555 -3.0657 -0.00638748 0.0737824 -0.00666913 -0.00444333 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2206 2207 2.42826 -0.25274 -0.116226 -0.0118247 0.066264 -0.142314 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2157 2207 0.128899 -3.02135 -0.0742188 0.0477688 -0.0059032 -0.0212365 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2207 2208 2.32818 -0.142037 0.145586 0.00823538 0.0484547 -0.0761591 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2158 2208 0.0492144 -3.08501 -0.160657 0.0422296 0.016621 0.0040718 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2208 2209 2.30257 -0.272176 -0.102851 -0.010707 0.043215 -0.0985159 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2159 2209 0.106064 -3.24122 -0.200244 0.0723842 -0.00502528 -0.0629091 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2209 2210 2.45692 -0.193683 0.00993662 0.0094787 0.0368965 -0.0531162 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2160 2210 -0.0397761 -3.14273 -0.142255 0.046293 0.00345791 0.0754936 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2210 2211 2.51071 -0.198808 -0.0302144 0.00240251 0.0603905 -0.0309833 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2161 2211 0.0641557 -3.12435 -0.0299417 0.0699469 -0.000729235 -0.0175618 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2211 2212 2.49369 -0.0733512 -0.0799538 -0.00157619 0.0377967 -0.102628 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2162 2212 -0.041255 -3.08557 -0.0228275 0.0864277 -0.00843774 -0.00971821 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2212 2213 2.39006 -0.153298 0.0373865 -0.0226361 0.0519442 -0.0801719 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2163 2213 0.0304574 -3.11691 -0.160732 0.046151 -0.015834 0.0374166 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2213 2214 2.43932 -0.0730176 -0.088475 -0.00612907 0.0509844 -0.105423 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2164 2214 0.108739 -3.00643 0.027084 0.085755 0.00694204 -0.0350078 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2214 2215 2.18211 -0.134376 -0.15483 -0.00990024 0.0410178 -0.130337 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2165 2215 0.206983 -3.06189 -0.111523 0.0529433 -0.0110484 0.0261857 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2215 2216 2.41499 -0.0178778 0.040534 -0.0208511 0.0657067 -0.0748808 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2166 2216 -0.038263 -3.10795 -0.172717 0.0410832 0.00226538 0.0363367 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2216 2217 2.23393 -0.421369 -0.0605318 -0.0122319 0.04604 -0.116962 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2167 2217 -0.0311467 -3.33994 -0.168698 0.0585983 -0.00533927 0.0196479 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2217 2218 2.28824 -0.187991 0.266978 -0.00985517 0.0449668 -0.123766 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2168 2218 0.0277269 -3.02926 -0.0189177 0.076134 0.00562826 -0.0883684 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2218 2219 2.21914 -0.0891997 0.0758099 -0.00422216 0.0621502 -0.0502196 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2169 2219 -0.132009 -3.20052 -0.124892 0.0752632 0.00978722 -0.0185529 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2219 2220 2.28897 -0.277102 -0.0897139 0.00585621 0.0325006 -0.0626968 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2170 2220 0.0515657 -3.19811 -0.0226816 0.0722133 0.0038119 -0.0238968 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2220 2221 2.40356 -0.0794056 -0.0707853 0.00827225 0.042917 -0.0745777 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2171 2221 0.0020289 -3.0789 -0.105971 0.0642963 0.000587239 0.0634684 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2221 2222 2.41028 -0.240465 -0.00656688 -0.013988 0.0423601 -0.207671 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2172 2222 -0.089643 -3.07374 0.0917028 0.07227 0.0203225 -0.00457888 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2222 2223 2.21486 -0.265447 -0.108695 -0.00823859 0.0416198 -0.107906 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2173 2223 0.0348587 -3.13613 -0.181005 0.0703685 0.00818457 -0.0208879 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2223 2224 2.35291 -0.0587143 0.16297 -0.00911025 0.0251222 -0.0962579 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2174 2224 -0.00313106 -3.06027 -0.147292 0.0826754 0.0110752 -0.0888304 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2224 2225 2.49824 -0.381568 -0.247656 0.0183914 0.0503724 -0.0649581 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2175 2225 -0.175605 -3.17031 -0.199502 0.0490859 0.000529661 0.00392985 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2225 2226 2.38142 -0.166439 -0.211008 0.0036302 0.044916 -0.106245 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2176 2226 -0.0534163 -3.00006 0.0805199 0.0566234 0.00399041 0.0467162 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2226 2227 2.27315 -0.201948 0.145509 0.0162738 0.0444936 -0.112116 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2177 2227 0.0729397 -3.10352 -0.257411 0.050738 0.0234286 0.0101824 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2227 2228 2.13866 -0.323873 0.0584076 0.00628432 0.0501886 -0.0786884 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2178 2228 -0.129155 -3.00117 -0.209532 0.0635982 -0.00349307 -0.0127521 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2228 2229 2.24573 -0.226832 -0.0876004 -0.00226324 0.0416601 -0.0834806 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2179 2229 -0.113299 -3.05684 -0.210092 0.0476924 0.00343535 0.0287745 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2229 2230 2.14541 -0.0988302 -0.00688579 0.000161036 0.0440841 -0.121684 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2180 2230 -0.0189862 -3.10925 0.00164508 0.0754132 -0.00609559 -0.0495884 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2230 2231 2.26833 -0.119201 -0.16057 -0.00263417 0.0678643 -0.0387118 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2181 2231 -0.0587379 -3.11642 -0.124486 0.0634916 0.0135817 0.0329516 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2231 2232 2.20321 -0.234994 -0.0591747 -0.00743613 0.0634624 -0.0870604 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2182 2232 -0.0113093 -3.08881 -0.0505008 0.0722501 0.0104092 -0.00702917 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2232 2233 2.30716 -0.30245 -0.0345714 0.00339953 0.0645713 -0.088468 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2183 2233 0.0726105 -3.07909 -0.0203768 0.0416527 0.00104335 -0.00793801 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2233 2234 2.34224 -0.0479596 -0.117307 0.0170189 0.0467825 -0.144716 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2184 2234 -0.0302362 -3.11005 -0.154014 0.0596551 -0.0105178 0.0172454 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2234 2235 2.10604 -0.211645 -0.0377961 -0.00254966 0.0262045 -0.107494 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2185 2235 0.15347 -2.98528 -0.0187968 0.0567387 0.00452622 -0.030051 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2235 2236 2.18674 -0.387761 -0.0670731 -0.02454 0.0492286 -0.13848 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2186 2236 -0.0476083 -2.98281 -0.0224559 0.0509072 -0.00193434 -0.0683612 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2236 2237 2.29351 -0.21551 -0.127336 -0.00939725 0.0474332 -0.0526786 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2187 2237 -0.0408969 -3.07651 -0.124193 0.0675363 -0.00591591 -0.0189927 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2237 2238 2.21828 -0.0361587 -0.149308 0.00145389 0.0522492 -0.137814 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2188 2238 -0.0176007 -2.96329 -0.182624 0.0487616 0.00270851 0.00544472 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2238 2239 2.13603 -0.438616 0.185176 -0.0103 0.0397437 -0.192253 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2189 2239 -0.173644 -2.93198 -0.218538 0.0601447 0.0189924 -0.000201178 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2239 2240 2.14175 -0.0934289 -0.0927082 -0.0115379 0.0293668 -0.139331 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2190 2240 -0.0104062 -3.19554 -0.0683765 0.0504799 -0.000922227 0.0737575 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2240 2241 2.27455 -0.0841658 -0.153554 -0.00610606 0.0503873 -0.134453 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2191 2241 -0.079757 -3.04263 -0.129327 0.0551978 -0.00137589 -0.0517119 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2241 2242 2.40569 -0.0856973 0.00508491 -0.00437298 0.0272206 -0.119376 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2192 2242 0.259483 -3.19725 -0.012703 0.0574886 0.00932987 0.0208732 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2242 2243 2.19892 -0.305506 -0.00208666 -0.00105475 0.0379288 -0.15478 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2193 2243 0.252445 -2.99016 -0.0735526 0.0593516 -0.00320603 -0.0113615 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2243 2244 2.10773 -0.261746 -0.20281 -0.0043918 0.0420619 -0.0945009 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2194 2244 -0.0730365 -3.10255 -0.113453 0.0361795 -0.00759446 -0.00207097 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2244 2245 2.20503 -0.09637 -0.0172909 0.00490303 0.0515887 -0.0251422 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2195 2245 -0.0571928 -3.09838 -0.100858 0.0641565 0.0120953 0.0380407 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2245 2246 2.11452 -0.240469 -0.0303933 0.00913271 0.0391608 -0.0474607 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2196 2246 -0.0409103 -2.9799 -0.196964 0.0685299 -0.00212445 -0.0316318 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2246 2247 2.08407 -0.393739 -0.0400024 0.00768771 0.0587528 -0.16516 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2197 2247 -0.133508 -3.32853 -0.069374 0.0735004 -0.0021991 -0.0651638 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2247 2248 2.16682 -0.247001 -0.208535 -0.0017154 0.0496419 -0.119736 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2198 2248 0.095991 -3.06765 0.0395367 0.0590997 -0.00565179 0.0272462 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2248 2249 2.1459 -0.111355 0.0157882 -0.0203288 0.057114 -0.13931 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2199 2249 0.00152709 -3.28254 -0.19906 0.0686271 -0.00888458 0.0494557 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2249 2250 2.01073 -0.0475806 0.0156337 0.00332742 0.0484108 -0.152279 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2200 2250 0.0731715 -3.05511 -0.168677 0.0610033 0.000739234 0.0470764 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2250 2251 2.12883 -0.174054 -0.0828055 0.0077702 0.0451207 -0.130534 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2201 2251 0.0318476 -3.08408 0.0372244 0.0556236 -0.0161512 -0.0249414 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2251 2252 2.08477 0.0094325 0.194089 0.00578599 0.0405357 -0.0935046 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2202 2252 0.135354 -3.00065 -0.070474 0.0465842 0.00553537 0.0905542 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2252 2253 2.12322 -0.15965 -0.0210489 -0.00373519 0.0338394 -0.159176 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2203 2253 0.0621182 -2.99876 -0.126039 0.0566084 -0.00676457 0.0327106 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2253 2254 2.2382 -0.290356 0.145082 -0.0111957 0.0481654 -0.146779 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2204 2254 0.141866 -3.13732 -0.194417 0.0781477 -0.010372 0.0650235 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2254 2255 2.02312 -0.2504 0.0288613 -0.0150235 0.0288631 -0.117621 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2205 2255 -0.00107366 -3.00815 -0.0399029 0.071044 -0.00886316 0.0360928 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2255 2256 1.94161 -0.195137 -0.0529264 0.000324258 0.036713 -0.16058 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2206 2256 -0.00468805 -2.9346 -0.340954 0.0578146 -0.0165249 -0.0391668 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2256 2257 2.05382 -0.316164 -0.000388159 -0.0104427 0.0698705 -0.0220898 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2207 2257 -0.0641324 -3.197 -0.0476484 0.0594176 -0.0246235 0.000199991 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2257 2258 1.97607 -0.347581 -0.118434 -0.0141743 0.0310101 -0.069045 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2208 2258 -0.0593136 -3.18147 -0.154494 0.0651677 -0.00601506 -0.00147135 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2258 2259 1.89973 -0.111151 -0.179496 -0.00218827 0.0422617 -0.0715735 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2209 2259 0.122889 -3.17773 0.0533363 0.0612789 0.0146025 0.0545342 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2259 2260 2.01897 -0.0903023 -0.136324 -0.0031832 0.0373394 -0.0624987 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2210 2260 0.0852201 -3.03755 -0.00071156 0.0646322 0.0163628 -0.050478 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2260 2261 2.12452 -0.0722184 -0.164085 -0.000303897 0.0277105 -0.0816322 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2211 2261 0.0888489 -2.96886 -0.0838832 0.059673 0.0107608 0.00195151 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2261 2262 1.90337 -0.126811 -0.134714 0.0127164 0.0457254 -0.134046 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2212 2262 -0.0848152 -2.93901 -0.11944 0.0527436 0.00334897 -0.0398191 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2262 2263 1.99664 -0.107199 -0.0734655 0.00788355 0.0653937 -0.156745 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2213 2263 -0.0982209 -3.02872 0.0709948 0.0521799 0.016494 0.0290343 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2263 2264 2.08043 -0.227108 -0.0959392 0.00651182 0.0401788 -0.146968 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2214 2264 0.170761 -3.07959 -0.187069 0.0814214 0.0024925 -0.0158149 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2264 2265 1.99483 -0.145478 -0.0256797 -0.00557818 0.044942 -0.161309 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2215 2265 0.0611452 -3.00291 -0.0804721 0.0491091 -0.0148528 -0.0196653 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2265 2266 2.01374 -0.191152 -0.200787 -0.00457746 0.0380285 -0.113309 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2216 2266 0.0389333 -3.1105 -0.125301 0.0595345 -0.00788476 -0.0385879 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2266 2267 1.93553 -0.221268 -0.12302 -0.0140487 0.0499578 -0.10009 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2217 2267 0.0530079 -3.1224 -0.106622 0.0735793 0.00467758 -0.0632729 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2267 2268 2.02526 -0.123949 -0.13481 0.00820823 0.0390393 -0.150725 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2218 2268 0.110224 -3.18825 -0.123779 0.0479409 -0.0118006 0.0270549 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2268 2269 1.92607 -0.224127 0.0275058 -0.0063251 0.0142911 -0.0817314 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2219 2269 0.0352732 -2.99297 -0.122349 0.0785783 -0.00703558 0.0105912 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2269 2270 2.04498 -0.12889 -0.0343222 0.00113892 0.0371032 -0.12962 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2220 2270 -0.11259 -3.10774 0.00556954 0.061117 -0.0196152 0.0178915 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2270 2271 2.17281 -0.255601 -0.000481343 0.00883018 0.0489576 -0.157326 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2221 2271 0.0525041 -3.05159 -0.200526 0.0551212 -0.00266242 0.0289833 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2271 2272 1.99601 -0.159212 -0.152885 -0.00188707 0.0358892 -0.0943433 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2222 2272 -0.0463186 -3.01473 -0.0436129 0.0750965 -0.00902345 -0.029304 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2272 2273 1.90808 -0.15794 0.107742 -0.00454947 0.0282355 -0.130326 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2223 2273 -0.201168 -3.11363 0.0762748 0.0480078 -0.0131164 0.0348233 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2273 2274 1.94003 -0.103868 -0.0945336 -0.00926562 0.0254767 -0.0847906 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2224 2274 -0.00791141 -2.98722 -0.0521449 0.0697366 9.43602e-05 -0.0255034 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2274 2275 1.99659 -0.119079 0.0962734 -0.00696213 0.0495352 -0.0625021 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2225 2275 0.236758 -3.08478 -0.170701 0.069919 0.00181331 0.0262023 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2275 2276 2.00207 -0.192687 0.00795414 -0.00197572 0.025751 -0.0779769 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2226 2276 -0.0103581 -3.04668 -0.0377333 0.068364 0.0127543 0.00615847 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2276 2277 2.07027 -0.234872 -0.0713098 0.00114781 0.0427079 -0.0868508 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2227 2277 0.153741 -3.04103 -0.125169 0.0616774 -0.00353131 -0.00328143 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2277 2278 1.69467 -0.280225 -0.125107 -0.014888 0.0422972 -0.120457 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2228 2278 0.142356 -3.12135 0.0522025 0.0751974 0.0141556 -0.0277364 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2278 2279 1.93965 -0.285605 0.02596 0.0160656 0.0529081 -0.0883982 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2229 2279 -0.147522 -2.92637 -0.175416 0.0568251 0.0202183 0.0239143 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2279 2280 2.10948 -0.229895 0.0235473 0.011683 0.0240393 -0.158176 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2230 2280 -0.0262539 -3.24955 -0.281895 0.0563195 0.00572416 -0.0636022 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2280 2281 1.90619 -0.125626 -0.0514883 -0.0158303 0.0315251 -0.15712 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2231 2281 -0.0801277 -3.06658 0.0321917 0.082781 0.00434812 0.0554064 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2281 2282 1.90665 -0.151257 0.0525089 -0.0139749 0.0432134 -0.150882 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2232 2282 0.0209947 -3.17195 0.0299715 0.0665821 -0.000188366 -0.0613439 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2282 2283 2.00813 -0.125643 0.000770173 0.00260907 0.0324244 -0.087986 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2233 2283 0.0453151 -3.18292 -0.117051 0.0486394 0.0131834 0.0306455 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2283 2284 1.82385 -0.233781 -0.124276 -0.00232502 0.0386997 -0.0966375 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2234 2284 -0.14367 -3.17219 -0.186889 0.0564919 -0.0167339 0.0287229 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2284 2285 1.70843 -0.0746772 0.0935637 0.00524045 0.0337941 -0.062141 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2235 2285 0.236379 -2.99963 -0.119173 0.0601594 0.00692067 -0.0228452 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2285 2286 1.77948 -0.077969 -0.067751 0.00917599 0.0393393 -0.0919151 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2236 2286 0.213813 -3.05517 0.0100068 0.0524267 -0.0113694 -0.0530015 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2286 2287 1.98606 -0.383365 -0.00625424 0.00984569 0.0310147 -0.0902957 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2237 2287 -0.0393351 -2.88869 0.0161872 0.0603079 -0.0100557 -0.00528367 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2287 2288 1.79612 -0.220759 -0.251684 0.0104236 0.0222496 -0.0697312 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2238 2288 0.0736107 -3.12632 0.152321 0.0546737 0.00890132 0.0381808 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2288 2289 1.99977 -0.205718 -0.000534324 -0.0140142 0.0395994 -0.103718 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2239 2289 -0.075851 -3.08171 -0.142838 0.0666229 -0.00488493 -0.0309152 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2289 2290 1.7525 -0.0631915 -0.185304 0.000924595 0.0379304 -0.0793994 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2240 2290 -0.107804 -3.19145 -0.167181 0.0735432 0.0220161 0.0553523 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2290 2291 1.68723 0.0242981 -0.00989759 0.00760996 0.0482857 -0.173045 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2241 2291 0.148737 -2.87134 -0.122466 0.0642383 -0.00171842 0.0610499 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2291 2292 1.66644 -0.24247 -0.0224895 -0.0213625 0.0513636 -0.104588 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2242 2292 -0.0546812 -2.88389 -0.0250769 0.0756875 -0.0137589 0.056273 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2292 2293 2.01819 -0.343416 -0.193556 -0.00144894 0.036179 -0.087195 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2243 2293 -0.00924392 -3.19348 -0.127155 0.0677689 0.020185 0.0169812 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2293 2294 1.75246 -0.16815 -0.0230253 0.00566216 0.0582354 -0.125771 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2244 2294 0.0739248 -2.9843 -0.13323 0.0584267 0.0130617 0.0515137 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2294 2295 1.93289 -0.239617 -0.0117727 0.00365515 0.0298992 -0.0780965 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2245 2295 -0.0400843 -3.15058 -0.119844 0.0542231 0.000396853 0.0730314 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2295 2296 1.77148 -0.118496 -0.0111194 -0.00151149 0.0420747 -0.119993 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2246 2296 -0.0364043 -3.02858 0.107759 0.0772343 -0.015815 -0.00821643 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2296 2297 1.81996 -0.186001 -0.0486902 -0.00454247 0.0181332 -0.108845 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2247 2297 -0.0406195 -3.08942 -0.129353 0.0667155 -0.00581341 -0.0312832 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2297 2298 1.77331 -0.0498224 0.0217255 -0.010217 0.0348168 -0.09261 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2248 2298 0.0284754 -2.96216 -0.0420628 0.0618162 0.0044834 -0.0179297 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2298 2299 1.65931 -0.292628 0.0578421 -0.00576367 0.047659 -0.17516 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2249 2299 -0.0193531 -3.1636 -0.175718 0.0787027 0.000528871 -0.0241526 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2299 2300 1.77318 -0.310941 -0.174551 0.000555425 0.0209107 -0.130317 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2250 2300 0.0398398 -3.21735 -0.147889 0.0613103 0.0179527 -0.0361187 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2300 2301 1.72243 -0.172336 -0.109753 0.00242613 0.0381127 -0.173356 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2251 2301 -0.0816599 -3.05955 -0.158979 0.0459933 -0.00341656 -0.0192522 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2301 2302 1.7992 -0.224403 -0.0128009 -0.00343199 0.0131098 -0.122157 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2252 2302 -0.00257336 -3.1386 -0.280685 0.0586122 0.0131083 -0.0163823 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2302 2303 1.75965 -0.249577 0.136034 -0.00613886 0.0524706 -0.138956 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2253 2303 0.132974 -3.00218 0.0359249 0.0756309 -0.0114659 -0.000397207 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2303 2304 1.76409 -0.185013 -0.0770608 -0.0148895 0.0422085 -0.043041 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2254 2304 0.0288848 -3.26039 0.134843 0.0409434 0.0023404 0.00602437 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2304 2305 1.83324 -0.282671 -0.0339006 0.00622051 0.0350416 -0.198562 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2255 2305 -0.0724857 -3.02757 -0.0839962 0.0488436 -0.0109341 -0.00264741 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2305 2306 1.74034 -0.035354 -0.121631 0.0149805 0.0372442 -0.0218262 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2256 2306 0.130484 -3.04301 -0.22685 0.0754029 0.00757369 -0.0427814 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2306 2307 1.8047 -0.200601 0.0310601 0.00443299 0.0395201 -0.138584 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2257 2307 -0.0353496 -3.17349 -0.067022 0.0565632 -0.00448649 0.00385663 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2307 2308 1.57613 -0.160179 -0.0209339 -0.00996642 0.0310576 -0.140582 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2258 2308 0.00969587 -3.079 -0.0460786 0.0401618 -0.00510122 -0.0392891 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2308 2309 1.64404 0.108162 -0.117034 0.0055001 0.0329952 -0.113634 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2259 2309 -0.0836754 -3.00392 -0.154613 0.0536925 -0.00276224 0.0160155 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2309 2310 1.58565 -0.225276 0.10022 -0.00797713 0.0383131 -0.136049 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2260 2310 0.100764 -3.00648 -0.0132723 0.0585415 0.0053519 -0.030129 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2310 2311 1.67408 -0.316932 -0.086084 -0.0129738 0.0357313 -0.0987939 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2261 2311 0.0790994 -3.00102 -0.10434 0.0622258 0.00741124 -0.0361891 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2311 2312 1.57609 -0.130485 -0.220239 -0.00499883 0.0382758 -0.0964521 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2262 2312 0.0899121 -3.07788 -0.029679 0.0824342 -0.00889839 -0.0297055 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2312 2313 1.55001 -0.254157 -0.0226944 -0.000653448 0.0296712 -0.143224 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2263 2313 -0.0698989 -2.95737 0.0834808 0.0821205 -0.00163185 -0.0676646 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2313 2314 1.68585 -0.216812 -0.106093 -0.00518323 0.0252269 -0.0654312 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2264 2314 0.0671252 -3.11059 0.0243918 0.0503054 0.00679731 -0.0240203 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2314 2315 1.69411 -0.059591 0.00311116 0.00974437 0.0488963 -0.108483 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2265 2315 0.0467165 -3.03716 -0.104013 0.0570087 0.00113857 0.0152445 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2315 2316 1.53893 -0.309835 -0.115086 -0.000328106 0.0343123 -0.127533 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2266 2316 0.047945 -3.09847 -0.171384 0.0577874 -0.00254362 0.025939 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2316 2317 1.58762 -0.01135 0.0382817 -0.012901 0.0382787 -0.0614852 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2267 2317 0.0292439 -3.11168 -0.0168262 0.0608562 0.00688562 -0.0137257 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2317 2318 1.65334 -0.288916 0.0574487 -0.0183214 0.0545663 -0.142474 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2268 2318 -0.145639 -3.23678 -0.071963 0.064014 -0.0123887 -0.0122148 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2318 2319 1.69819 -0.236228 -0.115156 0.00361568 0.0414949 -0.142084 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2269 2319 -0.00823403 -3.01181 -0.284541 0.0639514 -0.0258121 -0.0256025 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2319 2320 1.5934 -0.0217161 -0.0405252 0.0196963 0.0413379 -0.039758 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2270 2320 0.0966246 -3.09019 -0.119338 0.0715683 -0.0109498 -0.00444543 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2320 2321 1.60879 0.0145946 -0.0767824 -0.010222 0.0188519 -0.205189 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2271 2321 0.0643968 -2.99221 -0.0939419 0.0418409 0.0105716 0.0292748 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2321 2322 1.6329 -0.0530947 -0.150271 -0.00748276 0.0169255 -0.15598 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2272 2322 -0.141084 -3.40945 -0.186194 0.0630113 0.00133289 0.0336639 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2322 2323 1.46763 -0.112863 0.0644892 0.00630233 0.0465265 -0.124096 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2273 2323 -0.0304286 -3.19964 -0.028086 0.0429345 -0.00061071 -0.0322583 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2323 2324 1.53786 -0.263344 0.106711 -0.0162013 0.0349607 -0.0594121 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2274 2324 -0.0755028 -3.03482 -0.277086 0.0727873 -0.00638227 -0.0183608 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2324 2325 1.51244 -0.249677 -0.18187 -0.00168789 0.0301748 -0.0573436 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2275 2325 -0.0249669 -3.13455 -0.0897277 0.0738533 0.00178344 -0.0691228 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2325 2326 1.49086 -0.176673 0.228074 -0.0103946 0.0357081 -0.112772 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2276 2326 0.00886406 -3.00058 -0.232417 0.0582479 0.00139994 0.0434161 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2326 2327 1.53129 -0.0755849 -0.00869481 0.00393555 0.0288598 -0.142799 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2277 2327 -0.0573412 -3.12541 -0.0248082 0.0843084 -0.00525579 -0.00690728 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2327 2328 1.3665 -0.342648 0.021883 0.000878858 0.0319227 -0.121956 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2278 2328 0.151406 -3.14626 -0.0649404 0.0574064 -0.00913765 0.017077 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2328 2329 1.63015 -0.326397 -0.136252 -0.00336553 0.0243547 -0.0879005 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2279 2329 0.208943 -3.24225 -0.0761318 0.0785577 -0.0135863 -0.0768779 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2329 2330 1.39417 -0.0359897 -0.0200153 -0.0259372 0.03505 -0.0625316 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2280 2330 0.103572 -2.96804 -0.262925 0.0754555 -0.00749583 -0.015237 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2330 2331 1.44161 0.0638514 -0.0118146 -0.00336298 0.0284514 -0.180184 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2281 2331 0.0703312 -3.1521 -0.214529 0.0679059 -0.00138164 -0.0405607 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2331 2332 1.68199 -0.134449 -0.0126487 -0.0200837 0.0362823 -0.13884 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2282 2332 -0.05575 -2.95984 -0.0271593 0.0534981 0.00123027 -0.0653653 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2332 2333 1.48244 -0.169052 -0.0362219 -0.000210002 0.0320765 -0.0897336 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2283 2333 -0.104201 -3.05546 0.0934701 0.049229 -0.00654989 0.0197024 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2333 2334 1.41509 -0.299297 -0.000997348 0.00650446 0.0253976 -0.128072 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2284 2334 -0.0957512 -3.13413 -0.124297 0.060121 0.000242917 0.00220982 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2334 2335 1.36312 -0.0447894 -0.00277897 0.000418142 0.0484343 -0.145311 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2285 2335 0.0349026 -3.05373 -0.0246602 0.0686 -0.00561848 0.00627797 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2335 2336 1.43872 -0.108667 -0.0950942 0.00138579 0.0106616 -0.126514 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2286 2336 -0.0229829 -2.98571 0.0127402 0.0578854 0.00570252 -0.0110369 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2336 2337 1.38383 -0.146216 -0.0210355 0.0160248 0.0151822 -0.0972402 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2287 2337 0.204578 -3.19282 -0.0232178 0.0627186 0.0130144 -0.0164136 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2337 2338 1.50331 -0.0553864 -0.124124 0.00232334 0.0490295 -0.166948 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2288 2338 -0.00919614 -3.10004 -0.166525 0.0653096 0.00508945 -0.0374921 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2338 2339 1.50281 -0.18568 -0.0580225 -0.00536571 0.0313981 -0.0500758 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2289 2339 0.0794072 -3.05918 -0.13434 0.0649385 -0.00152763 -0.00976199 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2339 2340 1.48423 -0.264846 -0.055099 0.00797384 0.0455961 -0.0959498 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2290 2340 0.124318 -2.95537 -0.247582 0.0583225 0.00623077 -0.000870002 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2340 2341 1.36485 -0.0976642 -0.180627 0.0078959 0.0354614 -0.106692 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2291 2341 0.158017 -2.99723 -0.0902945 0.0634522 -0.00518194 -0.000705654 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2341 2342 1.53194 -0.182039 -0.0876279 -0.0102338 0.0445407 -0.121535 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2292 2342 -0.0838912 -3.144 -0.17146 0.0616257 0.000495449 0.0418406 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2342 2343 1.5589 -0.0554465 0.0256605 0.00551823 0.0307157 -0.161092 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2293 2343 -0.0562223 -3.12942 -0.12547 0.0422871 -0.00259562 0.0105056 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2343 2344 1.48766 -0.196837 0.0568543 0.00946243 0.0308738 -0.103151 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2294 2344 -0.0813901 -3.24565 -0.0308521 0.0736296 -0.0161328 0.0126117 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2344 2345 1.4279 -0.253921 0.126671 -0.00699944 0.0206204 -0.240319 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2295 2345 -0.0449535 -3.18971 -0.0162136 0.0489939 0.0119744 0.0272281 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2345 2346 1.42564 -0.1609 -0.0943723 0.00592762 0.01505 -0.195206 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2296 2346 0.00695177 -2.94834 -0.165641 0.0478688 0.00223715 0.0452543 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2346 2347 1.44731 -0.314619 0.00473586 -0.00459643 0.0385995 -0.127028 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2297 2347 -0.0419891 -3.27378 -0.0566923 0.0342261 0.00385122 -0.00899117 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2347 2348 1.3885 -0.162676 -0.0752585 -0.00916858 0.0345886 -0.183123 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2298 2348 -0.0643839 -3.17814 -0.0325685 0.0781708 0.0117731 0.0384214 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2348 2349 1.53003 -0.0655569 -0.034423 -0.0220057 0.0337815 -0.0339026 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2299 2349 0.155101 -2.99267 -0.0575645 0.0862995 0.0133551 0.00166607 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2349 2350 1.17426 -0.271174 0.058394 -0.0101931 0.04638 -0.0523797 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2300 2350 0.0143483 -3.15621 -0.235278 0.0695761 -0.00143256 -0.00698537 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2350 2351 1.50233 -0.019349 -0.00954614 0.00318434 0.0310995 -0.0988547 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2301 2351 0.025686 -3.18099 0.0236252 0.0374687 -0.00052816 -0.0231034 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2351 2352 1.5122 -0.0827326 -0.0294347 0.0193471 0.0215594 -0.136038 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2302 2352 0.13058 -3.00536 -0.0259078 0.0653042 -0.00928164 -0.0248387 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2352 2353 1.27187 -0.00353359 0.00199358 -0.00250159 0.0375395 -0.116383 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2303 2353 0.098438 -3.04361 -0.17478 0.0537095 -0.00203935 -0.0199316 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2353 2354 1.531 -0.251894 -0.0897503 -0.00768768 0.0302781 -0.150309 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2304 2354 0.151689 -3.09663 -0.154184 0.0636659 -0.00173934 0.0269123 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2354 2355 1.34621 -0.265306 -0.105326 0.00376238 0.0239642 -0.106495 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2305 2355 0.0301554 -2.87532 -0.133801 0.0832357 -0.000891657 0.0319418 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2355 2356 1.29027 -0.167265 -0.0110243 -0.0135948 0.0295908 -0.184445 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2306 2356 -0.0436607 -3.11451 0.0256047 0.0696562 -0.00322787 0.0428401 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2356 2357 1.43467 -0.134558 -0.159444 -0.0100503 0.0351553 -0.0995204 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2307 2357 0.137609 -3.01303 -0.0444566 0.0585284 -0.00403425 -0.0264392 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2357 2358 1.39576 -0.167194 0.103494 -0.0103307 0.0434836 -0.123856 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2308 2358 -0.00199259 -2.99604 -0.0836797 0.0631559 0.00832461 -0.0372798 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2358 2359 1.31826 -0.0968099 0.107417 0.0149888 0.0297234 -0.111337 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2309 2359 0.0820049 -3.06322 -0.112748 0.0698792 0.0077434 -0.026766 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2359 2360 1.26694 -0.164646 0.0728221 0.0103813 0.0495653 -0.169046 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2310 2360 -0.0647832 -3.10886 -0.115426 0.0663978 -0.00216099 -0.0396196 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2360 2361 1.13627 -0.0887732 -0.0331629 -0.0013004 0.0279233 -0.126378 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2311 2361 0.0559606 -2.90588 0.111901 0.0508102 -0.00440447 -0.0336929 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2361 2362 1.34974 -0.271104 -0.0434743 -0.00713999 0.00377137 -0.13518 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2312 2362 0.163394 -3.18081 0.00789267 0.0621498 0.00433713 0.00938405 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2362 2363 1.47457 -0.253676 0.0627284 0.00752493 0.0228907 -0.0771717 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2313 2363 0.0507714 -3.06287 -0.139605 0.0478517 0.00172452 -0.0135842 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2363 2364 1.19429 -0.118742 -0.0226078 -0.0049623 0.0329849 -0.161969 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2314 2364 0.0742564 -2.93125 0.00617903 0.051911 0.00359584 0.0323988 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2364 2365 1.4409 -0.207449 0.222692 -0.0133403 0.0437547 -0.117466 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2315 2365 0.00331017 -3.09833 -0.0890589 0.0517349 -0.0182802 0.0549729 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2365 2366 1.27185 -0.118601 0.121173 -0.0127061 0.018711 -0.124725 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2316 2366 0.0290666 -3.13497 -0.21771 0.0678812 0.00697804 0.0397592 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2366 2367 1.2889 -0.219168 -0.0358816 -0.00636138 0.0216098 -0.121669 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2317 2367 -0.262747 -3.00601 -0.158514 0.0674754 -0.00865707 -0.0271119 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2367 2368 1.2469 -0.174755 -0.0505601 -0.0028139 0.0279411 -0.159472 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2318 2368 0.0425717 -3.2411 -0.158981 0.0769582 -0.0138278 -0.0177188 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2368 2369 1.42156 -0.106308 0.143844 0.00257507 0.0262686 -0.155933 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2319 2369 -0.141221 -3.04945 -0.0539595 0.0438828 -0.00598622 -0.0346797 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2369 2370 1.12391 -0.18855 -0.235858 0.0105836 0.0259346 -0.0652671 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2320 2370 0.0549081 -3.24491 -0.12199 0.0602815 -0.0130468 0.0409746 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2370 2371 1.18916 -0.258598 -0.0428346 -0.0148937 0.036152 -0.155547 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2321 2371 -0.0218718 -3.11219 -0.0554362 0.0612933 -0.00695693 0.0282813 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2371 2372 1.20085 0.0183165 0.127728 -0.0142035 0.0164817 -0.150359 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2322 2372 0.189236 -3.18682 -0.243921 0.0503409 -0.00317759 -0.0515419 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2372 2373 1.45807 -0.186217 -0.107362 -0.00130825 0.0191404 -0.119813 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2323 2373 -0.0731614 -3.02883 -0.174227 0.0703798 -0.00756652 0.0193816 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2373 2374 1.18426 0.000197157 -0.0344764 0.00418012 0.0101834 -0.160714 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2324 2374 -0.00520651 -3.03417 -0.283874 0.0666407 -0.00639997 -0.0342001 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2374 2375 1.21769 -0.271659 -0.0521866 0.00170301 0.0295333 -0.137987 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2325 2375 -0.0228028 -3.07056 0.0573167 0.0631828 -0.0231212 0.0242733 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2375 2376 1.26801 -0.20578 -0.324607 -0.00695021 0.0220326 -0.103082 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2326 2376 -0.0621299 -3.18296 -0.0424051 0.0582665 -0.0100553 -0.0926792 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2376 2377 1.1643 -0.231669 0.0395846 -0.0193653 0.00970301 -0.179721 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2327 2377 0.0388514 -3.0083 -0.0987079 0.0618829 0.0024187 0.0173838 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2377 2378 1.0243 -0.0785003 0.00329079 -0.00360607 0.0291641 -0.153331 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2328 2378 -0.191664 -2.97448 0.0292238 0.0569084 -0.00833561 0.00551469 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2378 2379 1.08363 -0.205519 -0.204391 -0.00400729 0.0149072 -0.123346 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2329 2379 0.131935 -3.08183 -0.113085 0.0549028 0.0114832 0.0505372 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2379 2380 1.11237 -0.108409 0.194716 0.00778232 0.019014 -0.0229398 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2330 2380 -0.145342 -3.35581 -0.225241 0.0693832 0.0283036 -0.00764771 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2380 2381 1.14711 -0.202115 0.0472177 -0.00616451 0.0169251 -0.10334 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2331 2381 -0.107607 -3.05488 0.0839114 0.0558134 0.0151487 0.0132744 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2381 2382 1.25781 -0.0421506 -0.25557 -0.00949864 0.0472852 -0.142247 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2332 2382 0.321773 -3.06976 -0.253011 0.0786367 0.00492894 -0.0205592 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2382 2383 1.14591 -0.198373 0.105221 0.000123181 0.022432 -0.185041 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2333 2383 0.0338217 -3.05433 -0.088552 0.0631544 -0.00171597 -0.058275 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2383 2384 0.984793 -0.248879 -0.0517567 -0.00638012 0.0198466 -0.10684 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2334 2384 -0.0264963 -3.03963 -0.00924977 0.0629602 -0.00194704 0.016017 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2384 2385 1.16999 0.104466 -0.0044227 -0.00068721 0.0193063 -0.0817801 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2335 2385 -0.0202104 -3.26805 -0.192235 0.0692415 0.0110898 0.0427483 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2385 2386 1.20208 -0.0420889 0.163314 0.0100435 0.0173868 -0.0726622 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2336 2386 0.247688 -3.08574 0.0649253 0.0511622 0.00155898 -0.0360124 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2386 2387 1.12047 -0.212918 -0.0587477 -0.0022376 0.0218674 -0.107966 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2337 2387 -0.140196 -3.09267 -0.273355 0.0653758 -0.0278868 -0.0258696 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2387 2388 1.1279 -0.189501 0.129593 -0.00327702 0.0589108 -0.108792 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2338 2388 0.0717771 -3.1169 -0.0473226 0.0438506 0.012121 -0.0190223 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2388 2389 1.32964 -0.14278 0.0983584 -0.00197749 0.0317031 -0.14515 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2339 2389 0.0601862 -3.19448 0.0304527 0.0684157 0.00115953 0.0423894 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2389 2390 1.07822 -0.191734 -0.0171374 -0.00795168 0.025342 -0.077023 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2340 2390 -0.0178538 -3.13617 -0.0680685 0.0517115 -0.0143105 -0.0811578 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2390 2391 1.07505 -0.15458 -0.111723 0.0029201 0.0260859 -0.0920008 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2341 2391 -0.0210466 -2.98952 -0.08232 0.0770481 0.0143833 0.034793 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2391 2392 1.11633 -0.0580665 -0.0592771 -0.019217 0.0226051 -0.0403911 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2342 2392 0.00965012 -3.27615 0.00561593 0.0605299 -0.0129177 0.0652139 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2392 2393 1.00544 -0.183941 0.00773578 0.0219352 0.0255 -0.0693436 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2343 2393 0.0676061 -3.09994 -0.179616 0.0585756 -0.0162173 -0.047858 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2393 2394 1.04601 -0.117857 -0.0362245 -0.00392761 0.0128229 -0.14461 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2344 2394 -0.127267 -3.04509 -0.0207292 0.0475185 0.00616505 -0.0494123 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2394 2395 1.05325 -0.0347048 -0.0441859 -0.0124914 -0.000655675 -0.166959 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2345 2395 -0.10339 -3.05793 -0.190868 0.0472917 -0.0129218 -0.0202443 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2395 2396 1.09705 -0.236036 -0.0712261 0.0108056 0.0128371 -0.0670747 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2346 2396 -0.11939 -2.90669 -0.103871 0.0651987 0.0143111 -0.0445552 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2396 2397 1.00937 -0.135622 0.1453 0.0100368 0.00993705 -0.140917 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2347 2397 -0.0788292 -2.87156 0.05486 0.0587591 -0.0019809 0.00678225 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2397 2398 0.881329 0.0668708 0.110495 0.019662 0.0195875 -0.0921784 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2348 2398 -0.102262 -2.99928 0.0256153 0.0355337 -0.00811447 0.0288974 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2398 2399 1.18077 -0.0155792 0.0819929 -0.00986692 0.0169261 -0.130778 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2349 2399 0.120582 -3.00399 -0.121336 0.0636855 -0.00413597 0.0263499 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2399 2400 1.24287 -0.174488 0.0146951 -0.00288808 0.0147356 -0.134903 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2350 2400 0.0257293 -3.17807 0.0465324 0.0531606 0.00896709 -0.0121308 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2400 2401 1.02689 0.0488939 -0.0107248 0.00902402 0.0121253 -0.172868 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2351 2401 0.0806618 -3.17478 -0.0318378 0.0542997 -0.0123942 -0.00968929 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2401 2402 0.922211 -0.142718 -0.00329857 -0.00715726 0.0341412 -0.177995 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2352 2402 -0.0227351 -3.07862 -0.0456497 0.0424931 -0.000934033 -0.0899075 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2402 2403 0.948903 -0.100292 -0.118346 0.0117822 0.0128178 -0.106946 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2353 2403 0.114693 -3.13743 -0.309415 0.078277 -0.00280339 0.0107418 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2403 2404 0.957981 -0.167713 -0.0817728 -0.0105667 0.0269566 -0.149519 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2354 2404 -0.110838 -3.05052 -0.151266 0.0536218 0.000377916 -0.0448353 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2404 2405 0.966836 -0.0343883 -0.0641363 0.0241857 0.0081806 -0.0571673 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2355 2405 -0.0313224 -3.13363 -0.133837 0.0581501 0.00495669 -0.0266002 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2405 2406 1.14955 -0.0517833 -0.0981234 0.00969539 0.0141592 -0.103597 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2356 2406 -0.0272206 -3.22467 0.0305596 0.0514568 -0.023057 -0.055522 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2406 2407 0.880208 -0.116449 0.0152669 0.000122329 0.0238588 -0.0758653 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2357 2407 -0.204509 -3.13282 -0.160111 0.0502065 -0.00998833 0.00925931 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2407 2408 0.779758 -0.231602 -0.0116363 -0.00873717 0.00288593 -0.144172 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2358 2408 0.114301 -3.04663 -0.0879111 0.0661899 -0.00836855 0.00778534 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2408 2409 0.937779 -0.265218 -0.0727954 0.0122143 0.0308832 -0.140299 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2359 2409 0.116292 -3.14095 0.034373 0.0498044 -0.00724255 0.041764 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2409 2410 0.860547 -0.180693 -0.0319612 0.0113848 0.0129287 -0.0388687 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2360 2410 -0.16278 -2.95426 -0.0687947 0.070274 0.00232961 -0.0151955 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2410 2411 0.970943 -0.0328469 0.0245733 -0.00119069 0.0211168 -0.119534 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2361 2411 -0.11203 -3.06112 -0.203332 0.0830461 0.00290484 0.0438462 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2411 2412 0.910464 -0.176781 -0.0160987 0.0245812 0.0334807 -0.191983 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2362 2412 -0.0174788 -3.11391 -0.134562 0.0602173 0.00535236 -0.010384 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2412 2413 0.716215 -0.0672759 -0.180584 -0.0102212 0.0264646 -0.0464624 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2363 2413 0.0925205 -3.04294 -0.123194 0.0590799 0.0137483 0.0227182 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2413 2414 1.06891 -0.0613279 -0.0121096 -0.000282554 0.0216839 -0.126702 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2364 2414 0.163078 -3.02221 -0.305698 0.063076 0.0127644 0.0113707 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2414 2415 0.768765 -0.234965 0.115413 -0.0154947 0.0226744 -0.121295 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2365 2415 0.0898611 -3.11278 -0.230568 0.0714111 -0.0226521 -0.0105952 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2415 2416 0.809282 -0.174424 -0.0118621 -0.00412179 0.0121492 -0.176736 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2366 2416 0.178381 -3.07386 -0.0405802 0.069043 -0.0158566 0.00238133 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2416 2417 0.995156 -0.209479 -0.00575775 0.0102162 0.0130859 -0.153005 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2367 2417 0.0435759 -2.9972 -0.241973 0.037604 -0.000362601 -0.0413059 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2417 2418 0.779909 -0.0498183 0.0623948 0.00127184 0.0159649 -0.0681053 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2368 2418 0.0265457 -3.18037 -0.149991 0.0727304 -0.0141485 0.0111055 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2418 2419 0.899306 0.0789548 -0.00625073 0.0205097 0.0200221 -0.150305 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2369 2419 0.0404429 -3.25006 0.166059 0.0572778 0.0133024 0.00253824 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2419 2420 0.74652 -0.23748 -0.00681759 0.011293 0.0130525 -0.159856 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2370 2420 -0.037574 -2.96721 0.111019 0.0459223 0.00444773 -0.00182679 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2420 2421 0.936316 -0.120846 0.00285827 0.00993677 0.0327305 -0.171135 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2371 2421 -0.138485 -3.11691 -0.175378 0.0519402 0.00563299 0.0340938 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2421 2422 1.09531 -0.165679 0.0372133 0.0121574 0.0278475 -0.0809984 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2372 2422 0.0084985 -3.18732 0.0652056 0.0496632 -0.0101753 -0.00692508 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2422 2423 0.806983 -0.102447 0.0695419 0.00719742 0.0122177 -0.0885043 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2373 2423 -0.00079279 -3.12264 -0.0881471 0.0630097 -0.00112723 -0.103492 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2423 2424 0.930682 -0.290974 0.0122849 -0.00988208 0.00815466 -0.109388 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2374 2424 -0.0621977 -2.90502 -0.0614072 0.0765609 -0.00378335 0.0412032 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2424 2425 1.0523 -0.0942562 -0.0467388 -0.00653632 0.00487786 -0.192164 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2375 2425 0.0112092 -2.88165 -0.0909757 0.0588811 0.00831013 0.00112709 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2425 2426 0.824703 -0.109445 0.0693976 -0.0122318 0.0299445 -0.0911686 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2376 2426 0.0210469 -3.00441 -0.169417 0.0667231 -0.0136007 0.0227904 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2426 2427 0.75497 -0.0782575 -0.0804936 -0.0240997 0.0323592 -0.0775495 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2377 2427 -0.0539781 -3.20024 -0.219876 0.0691134 0.00964281 0.00626064 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2427 2428 0.96138 -0.188054 0.0592043 0.0149705 0.0247265 -0.0452124 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2378 2428 0.0936004 -2.91381 -0.0953071 0.050063 -0.0155988 0.0243915 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2428 2429 0.9152 -0.0855797 -0.0600578 0.0169479 0.012554 -0.0695441 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2379 2429 0.113707 -3.0694 -0.167609 0.0455064 -0.00244658 -0.0387184 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2429 2430 0.850647 -0.129926 -0.0223232 0.014384 0.0238581 -0.0969824 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2380 2430 0.0881312 -3.06934 -0.113937 0.0439417 -0.00228684 -0.0191046 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2430 2431 0.685435 -0.133605 0.077878 0.000473148 0.00381906 -0.152164 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2381 2431 -0.00909279 -3.01789 0.0443456 0.0559573 0.00761205 -0.0219043 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2431 2432 0.823047 -0.149762 -0.162131 0.000595512 0.0108591 -0.106331 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2382 2432 0.014111 -3.10677 -0.182714 0.0700237 -0.00159218 -0.00557386 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2432 2433 0.840293 -0.239467 -0.135264 -0.0144724 0.00844198 -0.0978062 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2383 2433 -0.119578 -3.14035 -0.0274269 0.0579008 -0.0131727 0.0571506 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2433 2434 0.705048 -0.335835 0.136846 0.00791271 0.0143495 -0.173525 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2384 2434 -0.000125601 -3.02959 -0.122347 0.0555076 0.00707249 0.0828599 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2434 2435 0.707182 -0.05967 0.1415 -0.00104398 0.0115305 -0.133776 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2385 2435 -0.145537 -2.97413 -0.0529797 0.0611963 -0.00321298 -0.0103854 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2435 2436 0.77111 -0.274935 -0.0170584 -0.00184025 0.014379 -0.179698 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2386 2436 0.0710403 -3.06771 -0.133144 0.0566319 0.000468333 0.0158188 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2436 2437 0.741301 -0.188334 0.027943 0.000597373 0.00806224 -0.113294 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2387 2437 0.137827 -3.10741 -0.174667 0.0697982 0.0200402 0.0258698 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2437 2438 0.718309 -0.043868 -0.132531 -0.00568739 0.02139 -0.098528 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2388 2438 0.0449994 -3.20431 -0.233903 0.0530649 0.0173331 -0.0346002 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2438 2439 0.927783 -0.188973 0.0167979 -0.00441738 0.0189338 -0.171666 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2389 2439 0.173802 -3.16614 -0.112143 0.0513729 0.00311768 0.0134471 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2439 2440 0.637889 -0.127063 -0.0647379 -0.000178452 0.0187992 -0.172063 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2390 2440 -0.0254123 -3.1022 0.00522851 0.0501957 -0.00583352 -0.0213677 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2440 2441 0.773295 -0.258757 -0.095237 0.00943016 0.00856157 -0.0998296 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2391 2441 0.0127781 -3.09094 -0.0970962 0.0703405 -0.00963293 0.0890245 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2441 2442 0.62647 -0.178776 0.0682368 -0.00420904 0.0156397 -0.129931 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2392 2442 -0.0676438 -2.86307 -0.226622 0.0758765 0.0172436 0.00180056 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2442 2443 0.676178 -0.102123 0.104527 0.00816574 0.0444575 -0.122909 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2393 2443 -0.039984 -3.169 -0.0995151 0.0639306 0.00420241 0.101485 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2443 2444 0.632994 -0.274214 -0.0604122 0.00101224 0.0143493 -0.118621 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2394 2444 0.0530277 -3.12004 -0.0117816 0.0678628 -0.013863 -0.0907453 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2444 2445 0.623687 -0.326872 0.105519 -0.00665688 0.0265943 -0.0992535 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2395 2445 0.0149223 -3.10563 -0.203804 0.0665157 -0.00132788 -0.0225485 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2445 2446 0.773107 -0.0253377 0.182962 0.0137606 -0.0108106 -0.0818229 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2396 2446 -0.0632931 -3.0343 -0.226887 0.0426537 -0.0047512 -0.019114 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2446 2447 0.673561 -0.154025 -0.0901807 -0.0191839 -0.0148791 -0.20063 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2397 2447 -0.0809943 -2.97586 -0.213127 0.0594819 0.00220003 0.0381013 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2447 2448 0.411284 -0.20703 0.136687 0.0116755 -0.00377624 -0.0912315 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2398 2448 -0.100975 -2.97909 -0.20848 0.0452265 -0.0196562 -0.00356765 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2448 2449 0.672445 0.0464331 -0.0631548 -0.0063544 0.0209633 -0.180151 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2399 2449 -0.0570497 -3.04541 0.0151781 0.0732119 -0.0085068 0.026724 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2449 2450 0.665612 -0.205443 -0.135734 0.00532383 0.0131119 -0.0472187 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2400 2450 0.0569956 -3.06219 -0.0730208 0.0520098 0.00849887 0.0840131 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2450 2451 0.615586 -0.0372146 0.0863717 0.00390466 0.00371816 -0.124666 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2401 2451 0.0233072 -3.05722 0.0254617 0.0649108 -0.00476468 0.0100399 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2451 2452 0.579888 -0.059038 0.0357022 0.0249911 0.000716339 -0.1355 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2402 2452 -0.0381196 -2.9876 -0.252388 0.066622 0.00910817 -0.000820153 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2452 2453 0.578913 -0.045787 -0.013608 0.0181774 0.0172093 -0.0783364 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2403 2453 -0.123723 -2.91757 -0.152678 0.0507555 -0.014463 -0.00911548 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2453 2454 0.706556 -0.09142 -0.0870603 -0.0080065 -0.00326606 -0.101556 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2404 2454 -0.00800361 -3.05468 -0.162409 0.0713166 -0.00185334 0.00664332 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2454 2455 0.3758 -0.147899 0.0169202 0.00450864 0.0199126 -0.150942 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2405 2455 0.0894775 -3.09437 -0.22297 0.0549127 0.0163251 0.02647 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2455 2456 0.568694 -0.038551 0.00840634 0.0138467 0.00624925 -0.170574 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2406 2456 0.0240355 -2.96653 -0.258981 0.0755388 0.00517666 0.0328618 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2456 2457 0.593057 0.068819 0.0774987 0.00654167 0.0153609 -0.131348 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2407 2457 0.11967 -2.95021 -0.0981865 0.0557045 -0.000920427 0.057171 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2457 2458 0.498043 -0.0344245 -0.0750707 0.00580262 0.00880905 -0.147671 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2408 2458 -0.0141258 -3.0485 -0.0227253 0.0731998 0.0126365 0.00610021 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2458 2459 0.582558 -0.0429044 0.070323 0.0200276 0.00527352 -0.155836 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2409 2459 -0.14116 -3.12543 -0.148791 0.067728 -0.0196802 -0.0100445 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2459 2460 0.386098 -0.36747 -0.134591 0.00426999 0.011702 -0.0948031 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2410 2460 0.10304 -3.05122 -0.131541 0.0626227 -0.0211071 -0.0233515 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2460 2461 0.517445 -0.176057 -0.047968 -0.00549729 0.0384751 -0.102036 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2411 2461 -0.0251865 -3.15388 0.0557313 0.0533006 0.0100787 0.0456261 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2461 2462 0.552157 -0.0370837 -0.040271 0.0116085 0.00494164 -0.161446 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2412 2462 0.078235 -2.91957 -0.14201 0.0798437 -0.000907816 -0.0167602 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2462 2463 0.640671 -0.150453 -0.147889 0.000563295 0.0220545 -0.0815588 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2413 2463 0.0262409 -2.93312 -0.106771 0.0427433 0.00550283 -0.0273735 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2463 2464 0.488227 -0.0813165 0.0287417 0.0122727 0.00419218 -0.114823 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2414 2464 -0.0625469 -3.04769 0.102979 0.0600207 -0.00990314 0.0486822 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2464 2465 0.462276 -0.310046 0.109169 -0.000971267 -0.00118784 -0.133384 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2415 2465 0.076364 -3.12365 -0.176031 0.0570426 -0.00229915 -0.0316881 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2465 2466 0.634099 -0.0424202 0.10411 -0.00345657 0.00234812 -0.0933225 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2416 2466 0.158965 -3.13729 -0.0695265 0.0666584 -0.0191502 -0.107546 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2466 2467 0.528947 0.104114 0.109304 0.00623237 0.0138401 -0.203818 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2417 2467 0.0951203 -3.09252 -0.211451 0.0646658 -0.0143471 -0.0400221 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2467 2468 0.420666 -0.280616 -0.1888 0.00663029 0.00363544 -0.0894842 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2418 2468 -0.0938255 -3.05576 -0.0404847 0.0581635 0.00142468 -0.0214397 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2468 2469 0.496087 0.0813272 0.0606169 0.00253762 0.0198426 -0.162761 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2419 2469 -0.106433 -3.00595 -0.0774184 0.0545304 0.000300188 -0.0402652 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2469 2470 0.432009 -0.218489 -0.223036 -0.000491628 0.013526 -0.168762 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2420 2470 -0.0431197 -3.14662 -0.145837 0.0474953 0.00819686 -0.0527404 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2470 2471 0.377241 -0.158585 0.125795 0.0161275 0.0248428 -0.19173 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2421 2471 0.0797938 -2.99855 -0.00896016 0.0650336 0.00721517 -0.0136197 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2471 2472 0.399956 -0.036309 -0.053913 -0.00497424 0.0117679 -0.135701 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2422 2472 -0.0744363 -3.11552 0.0459824 0.0609281 0.0180121 0.0401467 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2472 2473 0.419197 0.035327 0.281385 0.0109872 0.00726325 -0.118482 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2423 2473 -0.290219 -2.87447 -0.0431851 0.0400738 0.0207758 0.0127375 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2473 2474 0.344422 -0.276317 -0.0452232 0.0108431 -0.00762605 -0.106303 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2424 2474 -0.0905849 -3.13565 -0.19316 0.0562847 0.00449451 0.0507318 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2474 2475 0.530678 -0.278126 -0.0250559 0.00063751 0.00171984 -0.0959079 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2425 2475 0.113845 -2.91556 -0.0731655 0.0725515 -0.00157771 -0.0246475 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2475 2476 0.461974 0.0619353 -0.0616054 0.0121412 0.0213365 -0.0533189 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2426 2476 -0.0107406 -3.03889 -0.169288 0.0498789 -0.00523033 -0.019029 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2476 2477 0.299422 -0.0292875 -0.0874556 -0.00399893 0.0018028 -0.166862 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2427 2477 -0.259508 -3.04391 0.148407 0.0731842 0.00856545 -0.0250325 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2477 2478 0.452342 0.0281974 -0.0173345 0.00268463 0.0106544 -0.129739 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2428 2478 0.109832 -2.87685 -0.274584 0.077966 0.0130997 0.0253019 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2478 2479 0.618512 -0.0966368 0.15368 0.0159476 0.0037621 -0.14744 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2429 2479 0.0363237 -3.15614 -0.0869768 0.060985 0.019735 0.0523234 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2479 2480 0.435326 -0.200552 -0.0933764 0.00238797 0.0150303 -0.110618 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2430 2480 0.097677 -3.18419 0.0924348 0.0725214 -0.00781518 -0.0120098 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2480 2481 0.488551 -0.179534 -0.0753795 -0.00481112 0.00309579 -0.09719 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2431 2481 -0.0306665 -3.09426 -0.190765 0.0497534 -0.00735514 0.0678605 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2481 2482 0.368743 -0.169351 -0.064621 -0.0055098 -0.010371 -0.101829 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2432 2482 0.0722814 -2.84839 -0.162707 0.0524311 -0.0164076 -0.0461377 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2482 2483 0.424954 0.0182101 0.0646437 0.0114593 -0.00611225 -0.0964451 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2433 2483 -0.0290034 -2.91556 -0.125121 0.0627587 -0.0137413 0.00535325 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2483 2484 0.352777 -0.167919 0.0639258 0.00198547 0.0166012 -0.108284 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2434 2484 -0.0834858 -3.13496 -0.155794 0.0635078 0.0059674 -0.0463205 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2484 2485 0.394039 0.0109916 0.133616 0.00200869 0.00264847 -0.13324 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2435 2485 -0.0846365 -3.10733 -0.151788 0.0632132 -0.000311284 0.0202125 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2485 2486 0.170097 -0.0569364 0.133644 0.00309653 0.00135699 -0.212218 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2436 2486 0.0439303 -3.04648 -0.0140596 0.0750174 0.00428768 0.0285491 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2486 2487 0.291923 -0.350715 -0.0506407 0.0215878 0.00775374 -0.0609982 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2437 2487 0.101117 -2.90752 -0.24059 0.0627272 0.0140629 0.00778796 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2487 2488 0.311796 -0.0618708 -0.0102698 0.0074356 0.0222731 -0.147975 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2438 2488 0.0335922 -2.95863 -0.126668 0.0886017 -0.00747481 -0.0944425 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2488 2489 0.413104 -0.13094 -0.140749 -0.000846373 0.0163652 -0.130555 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2439 2489 -0.0502104 -2.91591 0.130835 0.0661883 -0.00659339 -0.0380005 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2489 2490 0.379747 -0.177883 0.0447272 0.0014528 0.0169824 -0.073449 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2440 2490 0.0375954 -3.02576 -0.0402119 0.072014 0.00884395 -0.0466011 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2490 2491 0.354395 -0.0230735 -0.0789061 0.0129899 0.0344318 -0.187288 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2441 2491 0.0977798 -3.22841 -0.0112792 0.0797777 0.00936993 -0.0301513 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2491 2492 0.166564 -0.170059 0.0495732 0.0141237 -0.00888752 -0.118969 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2442 2492 -0.0458312 -2.91145 0.0499288 0.0660945 0.0182401 0.0406457 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2492 2493 0.293104 -0.104138 -0.110184 -0.00748046 -0.000512588 -0.0690703 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2443 2493 0.130498 -3.03704 -0.0405533 0.0627682 0.00119051 0.0827094 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2493 2494 0.286681 0.0800986 -0.140534 -0.0117125 0.00136767 -0.135267 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2444 2494 -0.00111674 -2.87381 -0.032075 0.0685083 0.00880956 -0.0441376 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2494 2495 0.451006 0.0159923 -0.110392 -0.0128448 0.0120649 -0.121651 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2445 2495 -0.0223247 -3.03891 -0.157711 0.0603474 -0.023171 -0.025239 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2495 2496 0.407636 -0.207573 -0.132776 -0.00180566 -0.00803491 -0.0849705 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2446 2496 0.073903 -3.10015 -0.0759222 0.0604432 0.00807335 0.0386886 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2496 2497 0.339458 -0.0490249 -0.183052 0.0126326 0.00427634 -0.121645 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2447 2497 -0.095026 -3.19391 -0.103208 0.0788101 -0.012198 -0.0036844 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2497 2498 0.182255 -0.232472 -0.0869942 0.0112859 0.00743998 -0.0934717 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2448 2498 -0.234395 -3.01476 0.126794 0.0599249 0.00359686 -0.0488592 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2498 2499 0.277322 -0.0641475 0.0477913 -0.00287415 0.000789099 -0.143286 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2449 2499 -0.110695 -3.08307 -0.11704 0.067227 0.00205309 0.0105472 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 diff --git a/examples/Data/sphere2500_groundtruth.txt b/examples/Data/sphere2500_groundtruth.txt new file mode 100644 index 000000000..1bdebb071 --- /dev/null +++ b/examples/Data/sphere2500_groundtruth.txt @@ -0,0 +1,4949 @@ +EDGE3 0 1 0.258134 -0.0450052 -0.000686593 0.00153957 0.00500934 0.125564 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1 2 0.265802 -0.044524 -0.000726337 0.00154919 0.00516271 0.125558 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2 3 0.27347 -0.0440429 -0.000767259 0.00155881 0.00531607 0.125552 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 3 4 0.281136 -0.0435619 -0.00080936 0.00156844 0.00546942 0.125545 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 4 5 0.288803 -0.043081 -0.000852639 0.00157806 0.00562276 0.125539 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 5 6 0.296469 -0.0426002 -0.000897096 0.00158767 0.00577609 0.125532 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 6 7 0.304135 -0.0421196 -0.000942729 0.00159729 0.00592942 0.125524 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 7 8 0.3118 -0.041639 -0.000989541 0.0016069 0.00608273 0.125517 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 8 9 0.319465 -0.0411586 -0.00103753 0.00161651 0.00623604 0.12551 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 9 10 0.327129 -0.0406782 -0.00108669 0.00162612 0.00638934 0.125502 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 10 11 0.334793 -0.040198 -0.00113703 0.00163573 0.00654263 0.125494 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 11 12 0.342456 -0.0397179 -0.00118855 0.00164533 0.00669591 0.125486 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 12 13 0.350119 -0.039238 -0.00124124 0.00165493 0.00684918 0.125478 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 13 14 0.357781 -0.0387582 -0.00129511 0.00166453 0.00700244 0.125469 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 14 15 0.365443 -0.0382785 -0.00135016 0.00167412 0.00715568 0.125461 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 15 16 0.373104 -0.0377989 -0.00140637 0.00168372 0.00730892 0.125452 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 16 17 0.380765 -0.0373195 -0.00146377 0.00169331 0.00746215 0.125443 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 17 18 0.388425 -0.0368402 -0.00152233 0.0017029 0.00761537 0.125434 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 18 19 0.396084 -0.0363611 -0.00158207 0.00171248 0.00776857 0.125425 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 19 20 0.403743 -0.0358821 -0.00164299 0.00172206 0.00792176 0.125415 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 20 21 0.411401 -0.0354033 -0.00170507 0.00173164 0.00807495 0.125405 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 21 22 0.419059 -0.0349246 -0.00176833 0.00174122 0.00822812 0.125395 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 22 23 0.426716 -0.0344461 -0.00183276 0.00175079 0.00838127 0.125385 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 23 24 0.434372 -0.0339677 -0.00189837 0.00176036 0.00853442 0.125375 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 24 25 0.442028 -0.0334895 -0.00196514 0.00176993 0.00868755 0.125365 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 25 26 0.449683 -0.0330115 -0.00203309 0.00177949 0.00884067 0.125354 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 26 27 0.457337 -0.0325336 -0.0021022 0.00178905 0.00899378 0.125343 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 27 28 0.464991 -0.0320559 -0.00217249 0.00179861 0.00914687 0.125332 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 28 29 0.472644 -0.0315784 -0.00224395 0.00180816 0.00929995 0.125321 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 29 30 0.480296 -0.0311011 -0.00231657 0.00181771 0.00945302 0.12531 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 30 31 0.487948 -0.0306239 -0.00239037 0.00182726 0.00960607 0.125298 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 31 32 0.495599 -0.0301469 -0.00246533 0.0018368 0.00975911 0.125286 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 32 33 0.503249 -0.0296701 -0.00254146 0.00184634 0.00991213 0.125274 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 33 34 0.510898 -0.0291935 -0.00261876 0.00185588 0.0100651 0.125262 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 34 35 0.518547 -0.0287171 -0.00269723 0.00186541 0.0102181 0.12525 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 35 36 0.526194 -0.0282409 -0.00277686 0.00187494 0.0103711 0.125237 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 36 37 0.533841 -0.0277648 -0.00285766 0.00188446 0.0105241 0.125225 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 37 38 0.541488 -0.027289 -0.00293962 0.00189398 0.010677 0.125212 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 38 39 0.549133 -0.0268134 -0.00302275 0.0019035 0.01083 0.125199 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 39 40 0.556777 -0.026338 -0.00310705 0.00191301 0.0109829 0.125185 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 40 41 0.564421 -0.0258628 -0.0031925 0.00192252 0.0111358 0.125172 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 41 42 0.572064 -0.0253877 -0.00327913 0.00193202 0.0112887 0.125158 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 42 43 0.579706 -0.024913 -0.00336691 0.00194152 0.0114415 0.125144 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 43 44 0.587347 -0.0244384 -0.00345586 0.00195102 0.0115944 0.12513 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 44 45 0.594988 -0.023964 -0.00354597 0.00196051 0.0117472 0.125116 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 45 46 0.602627 -0.0234899 -0.00363724 0.00196999 0.0119 0.125102 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 46 47 0.610265 -0.023016 -0.00372967 0.00197948 0.0120528 0.125087 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 47 48 0.617903 -0.0225423 -0.00382327 0.00198895 0.0122056 0.125073 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 48 49 0.62554 -0.0220689 -0.00391802 0.00199843 0.0123584 0.125058 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 49 50 0.633175 -0.0215956 -0.00401393 0.0020079 0.0125111 0.125043 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 0 50 2.58718e-14 -3.05972 -0.0937068 0.0612327 0 4.88498e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 50 51 0.64081 -0.0211227 -0.00411101 0.00201736 0.0126638 0.125027 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1 51 2.72005e-14 -3.05972 -0.0937068 0.0612327 0 5.32907e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 51 52 0.648444 -0.0206499 -0.00420923 0.00202682 0.0128166 0.125012 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2 52 2.84217e-14 -3.05972 -0.0937068 0.0612327 4.44089e-16 5.32907e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 52 53 0.656077 -0.0201774 -0.00430862 0.00203628 0.0129692 0.124996 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 3 53 2.93099e-14 -3.05972 -0.0937068 0.0612327 4.44089e-16 6.21725e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 53 54 0.663708 -0.0197052 -0.00440917 0.00204573 0.0131219 0.12498 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 4 54 3.13083e-14 -3.05972 -0.0937068 0.0612327 4.44089e-16 6.21725e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 54 55 0.671339 -0.0192332 -0.00451087 0.00205517 0.0132746 0.124964 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 5 55 3.21965e-14 -3.05972 -0.0937068 0.0612327 4.44089e-16 5.32907e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 55 56 0.678969 -0.0187614 -0.00461372 0.00206461 0.0134272 0.124948 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 6 56 3.33067e-14 -3.05972 -0.0937068 0.0612327 4.44089e-16 5.77316e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 56 57 0.686598 -0.0182899 -0.00471773 0.00207405 0.0135798 0.124932 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 7 57 3.5083e-14 -3.05972 -0.0937068 0.0612327 4.44089e-16 7.10543e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 57 58 0.694226 -0.0178187 -0.0048229 0.00208348 0.0137324 0.124915 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 8 58 3.75255e-14 -3.05972 -0.0937068 0.0612327 4.44089e-16 6.66134e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 58 59 0.701852 -0.0173477 -0.00492922 0.0020929 0.013885 0.124898 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 9 59 3.84137e-14 -3.05972 -0.0937068 0.0612327 4.44089e-16 5.77316e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 59 60 0.709478 -0.0168769 -0.00503669 0.00210232 0.0140375 0.124881 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 10 60 3.93019e-14 -3.05972 -0.0937068 0.0612327 4.44089e-16 6.66134e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 60 61 0.717103 -0.0164065 -0.00514532 0.00211174 0.01419 0.124864 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 11 61 4.17999e-14 -3.05972 -0.0937068 0.0612327 4.44089e-16 7.99361e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 61 62 0.724726 -0.0159363 -0.0052551 0.00212114 0.0143425 0.124847 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 12 62 4.44367e-14 -3.05972 -0.0937068 0.0612327 4.44089e-16 7.54952e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 62 63 0.732349 -0.0154664 -0.00536603 0.00213055 0.014495 0.124829 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 13 63 4.54081e-14 -3.05972 -0.0937068 0.0612327 4.44089e-16 6.66134e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 63 64 0.73997 -0.0149967 -0.00547811 0.00213995 0.0146475 0.124812 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 14 64 4.67404e-14 -3.05972 -0.0937068 0.0612327 4.44089e-16 7.54952e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 64 65 0.74759 -0.0145273 -0.00559134 0.00214934 0.0147999 0.124794 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 15 65 4.38538e-14 -3.05972 -0.0937068 0.0612327 4.44089e-16 7.10543e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 65 66 0.755209 -0.0140583 -0.00570571 0.00215873 0.0149524 0.124776 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 16 66 3.93019e-14 -3.05972 -0.0937068 0.0612327 4.44089e-16 6.21725e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 66 67 0.762827 -0.0135894 -0.00582124 0.00216811 0.0151048 0.124757 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 17 67 3.39728e-14 -3.05972 -0.0937068 0.0612327 4.44089e-16 5.32907e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 67 68 0.770444 -0.0131209 -0.00593792 0.00217749 0.0152571 0.124739 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 18 68 2.88658e-14 -3.05972 -0.0937068 0.0612327 4.44089e-16 4.44089e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 68 69 0.77806 -0.0126527 -0.00605574 0.00218686 0.0154095 0.12472 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 19 69 2.35367e-14 -3.05972 -0.0937068 0.0612327 4.44089e-16 3.9968e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 69 70 0.785674 -0.0121847 -0.00617471 0.00219622 0.0155618 0.124701 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 20 70 1.95399e-14 -3.05972 -0.0937068 0.0612327 0 3.10862e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 70 71 0.793288 -0.0117171 -0.00629482 0.00220558 0.0157141 0.124682 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 21 71 1.15463e-14 -3.05972 -0.0937068 0.0612327 0 1.77636e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 71 72 0.8009 -0.0112497 -0.00641608 0.00221494 0.0158664 0.124663 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 22 72 8.21565e-15 -3.05972 -0.0937068 0.0612327 0 1.77636e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 72 73 0.808511 -0.0107826 -0.00653849 0.00222429 0.0160187 0.124644 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 23 73 2.22045e-16 -3.05972 -0.0937068 0.0612327 0 0 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 73 74 0.816121 -0.0103159 -0.00666204 0.00223363 0.0161709 0.124624 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 24 74 -2.9976e-15 -3.05972 -0.0937068 0.0612327 0 0 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 74 75 0.823729 -0.00984941 -0.00678673 0.00224296 0.0163231 0.124605 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 25 75 -1.15318e-14 -3.05972 -0.0937068 0.0612327 0 -2.22045e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 75 76 0.831336 -0.00938325 -0.00691256 0.00225229 0.0164753 0.124585 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 26 76 -1.4766e-14 -3.05972 -0.0937068 0.0612327 0 -2.22045e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 76 77 0.838942 -0.00891741 -0.00703954 0.00226162 0.0166275 0.124565 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 27 77 -2.34257e-14 -3.05972 -0.0937068 0.0612327 -4.44089e-16 -3.55271e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 77 78 0.846547 -0.00845188 -0.00716765 0.00227093 0.0167796 0.124544 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 28 78 -2.70894e-14 -3.05972 -0.0937068 0.0612327 -4.44089e-16 -3.55271e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 78 79 0.854151 -0.00798666 -0.00729691 0.00228025 0.0169318 0.124524 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 29 79 -3.64153e-14 -3.05972 -0.0937068 0.0612327 -4.44089e-16 -5.32907e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 79 80 0.861753 -0.00752177 -0.0074273 0.00228955 0.0170838 0.124503 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 30 80 -3.95239e-14 -3.05972 -0.0937068 0.0612327 -4.44089e-16 -5.32907e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 80 81 0.869354 -0.00705719 -0.00755883 0.00229885 0.0172359 0.124482 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 31 81 -4.86278e-14 -3.05972 -0.0937068 0.0612327 -4.44089e-16 -7.10543e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 81 82 0.876954 -0.00659294 -0.0076915 0.00230814 0.017388 0.124461 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 32 82 -5.17364e-14 -3.05972 -0.0937068 0.0612327 -4.44089e-16 -7.10543e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 82 83 0.884552 -0.00612901 -0.00782531 0.00231743 0.01754 0.12444 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 33 83 -5.77316e-14 -3.05972 -0.0937068 0.0612327 -4.44089e-16 -7.99361e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 83 84 0.892149 -0.00566541 -0.00796025 0.00232671 0.017692 0.124419 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 34 84 -6.4615e-14 -3.05972 -0.0937068 0.0612327 -8.88178e-16 -9.32587e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 84 85 0.899745 -0.00520214 -0.00809633 0.00233598 0.0178439 0.124397 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 35 85 -7.19425e-14 -3.05972 -0.0937068 0.0612327 -8.88178e-16 -9.76996e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 85 86 0.907339 -0.00473921 -0.00823354 0.00234525 0.0179959 0.124375 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 36 86 -7.88258e-14 -3.05972 -0.0937068 0.0612327 -8.88178e-16 -1.06581e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 86 87 0.914932 -0.00427662 -0.00837189 0.00235451 0.0181478 0.124353 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 37 87 -8.58758e-14 -3.05972 -0.0937068 0.0612327 -8.88178e-16 -1.15463e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 87 88 0.922523 -0.00381436 -0.00851136 0.00236376 0.0182997 0.124331 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 38 88 -9.31477e-14 -3.05972 -0.0937068 0.0612327 -8.88178e-16 -1.24345e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 88 89 0.930114 -0.00335245 -0.00865197 0.00237301 0.0184515 0.124309 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 39 89 -1.00475e-13 -3.05972 -0.0937068 0.0612327 -1.33227e-15 -1.37668e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 89 90 0.937702 -0.00289089 -0.00879371 0.00238225 0.0186033 0.124286 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 40 90 -1.08358e-13 -3.05972 -0.0937068 0.0612327 -1.33227e-15 -1.46549e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 90 91 0.94529 -0.00242967 -0.00893658 0.00239148 0.0187551 0.124264 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 41 91 -1.15241e-13 -3.05972 -0.0937068 0.0612327 -1.33227e-15 -1.5099e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 91 92 0.952876 -0.00196881 -0.00908058 0.00240071 0.0189069 0.124241 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 42 92 -1.23457e-13 -3.05972 -0.0937068 0.0612327 -1.33227e-15 -1.59872e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 92 93 0.96046 -0.0015083 -0.00922571 0.00240992 0.0190587 0.124218 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 43 93 -1.30562e-13 -3.05972 -0.0937068 0.0612327 -1.77636e-15 -1.68754e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 93 94 0.968043 -0.00104814 -0.00937197 0.00241914 0.0192104 0.124194 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 44 94 -1.38112e-13 -3.05972 -0.0937068 0.0612327 -1.77636e-15 -1.82077e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 94 95 0.975625 -0.000588348 -0.00951935 0.00242834 0.0193621 0.124171 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 45 95 -1.46549e-13 -3.05972 -0.0937068 0.0612327 -1.77636e-15 -1.86517e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 95 96 0.983205 -0.000128916 -0.00966786 0.00243754 0.0195137 0.124147 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 46 96 -1.54987e-13 -3.05972 -0.0937068 0.0612327 -1.77636e-15 -1.95399e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 96 97 0.990784 0.000330151 -0.00981749 0.00244673 0.0196654 0.124123 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 47 97 -1.63647e-13 -3.05972 -0.0937068 0.0612327 -2.22045e-15 -2.04281e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 97 98 0.998361 0.00078885 -0.00996825 0.00245591 0.019817 0.124099 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 48 98 -1.71418e-13 -3.05972 -0.0937068 0.0612327 -2.22045e-15 -2.13163e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 98 99 1.00594 0.00124718 -0.0101201 0.00246509 0.0199685 0.124075 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 49 99 -1.79967e-13 -3.05972 -0.0937068 0.0612327 -2.22045e-15 -2.22045e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 99 100 1.01351 0.00170513 -0.0102731 0.00247426 0.0201201 0.124051 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 50 100 -1.88534e-13 -3.05972 -0.0937068 0.0612327 -2.22045e-15 -2.30926e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 100 101 1.02108 0.00216271 -0.0104273 0.00248342 0.0202716 0.124026 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 51 101 -1.97287e-13 -3.05972 -0.0937068 0.0612327 -2.66454e-15 -2.39808e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 101 102 1.02865 0.00261991 -0.0105825 0.00249257 0.0204231 0.124002 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 52 102 -2.06057e-13 -3.05972 -0.0937068 0.0612327 -2.66454e-15 -2.4869e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 102 103 1.03622 0.00307673 -0.0107389 0.00250172 0.0205745 0.123977 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 53 103 -2.17382e-13 -3.05972 -0.0937068 0.0612327 -2.66454e-15 -2.66454e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 103 104 1.04379 0.00353317 -0.0108963 0.00251086 0.020726 0.123952 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 54 104 -2.24709e-13 -3.05972 -0.0937068 0.0612327 -2.66454e-15 -2.66454e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 104 105 1.05136 0.00398921 -0.0110549 0.00251999 0.0208774 0.123926 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 55 105 -2.30482e-13 -3.05972 -0.0937068 0.0612327 -2.66454e-15 -2.66454e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 105 106 1.05892 0.00444487 -0.0112147 0.00252911 0.0210287 0.123901 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 56 106 -2.42917e-13 -3.05972 -0.0937068 0.0612327 -3.10862e-15 -2.84217e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 106 107 1.06649 0.00490014 -0.0113755 0.00253823 0.0211801 0.123875 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 57 107 -2.53131e-13 -3.05972 -0.0937068 0.0612327 -3.55271e-15 -3.01981e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 107 108 1.07405 0.005355 -0.0115374 0.00254733 0.0213314 0.123849 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 58 108 -2.61124e-13 -3.05972 -0.0937068 0.0612327 -3.55271e-15 -3.01981e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 108 109 1.08161 0.00580948 -0.0117005 0.00255643 0.0214826 0.123823 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 59 109 -2.66898e-13 -3.05972 -0.0937068 0.0612327 -3.55271e-15 -3.01981e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 109 110 1.08917 0.00626355 -0.0118647 0.00256552 0.0216339 0.123797 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 60 110 -2.79554e-13 -3.05972 -0.0937068 0.0612327 -3.55271e-15 -3.19744e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 110 111 1.09672 0.00671721 -0.0120299 0.00257461 0.0217851 0.123771 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 61 111 -2.92433e-13 -3.05972 -0.0937068 0.0612327 -3.9968e-15 -3.37508e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 111 112 1.10428 0.00717048 -0.0121963 0.00258368 0.0219363 0.123744 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 62 112 -2.99372e-13 -3.05972 -0.0937068 0.0612327 -3.9968e-15 -3.37508e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 112 113 1.11183 0.00762333 -0.0123638 0.00259275 0.0220874 0.123717 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 63 113 -3.06477e-13 -3.05972 -0.0937068 0.0612327 -3.9968e-15 -3.37508e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 113 114 1.11939 0.00807577 -0.0125325 0.00260181 0.0222385 0.123691 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 64 114 -3.19078e-13 -3.05972 -0.0937068 0.0612327 -4.44089e-15 -3.55271e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 114 115 1.12694 0.00852779 -0.0127022 0.00261086 0.0223896 0.123663 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 65 115 -3.21076e-13 -3.05972 -0.0937068 0.0612327 -4.44089e-15 -3.73035e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 115 116 1.13448 0.0089794 -0.012873 0.00261991 0.0225406 0.123636 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 66 116 -3.24185e-13 -3.05972 -0.0937068 0.0612327 -4.44089e-15 -3.73035e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 116 117 1.14203 0.00943059 -0.0130449 0.00262894 0.0226916 0.123609 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 67 117 -3.25961e-13 -3.05972 -0.0937068 0.0612327 -4.44089e-15 -3.73035e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 117 118 1.14958 0.00988136 -0.013218 0.00263797 0.0228426 0.123581 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 68 118 -3.27738e-13 -3.05972 -0.0937068 0.0612327 -4.44089e-15 -3.73035e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 118 119 1.15712 0.0103317 -0.0133921 0.00264699 0.0229935 0.123553 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 69 119 -3.30846e-13 -3.05972 -0.0937068 0.0612327 -4.88498e-15 -3.73035e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 119 120 1.16466 0.0107816 -0.0135674 0.002656 0.0231445 0.123525 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 70 120 -3.31735e-13 -3.05972 -0.0937068 0.0612327 -4.88498e-15 -3.73035e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 120 121 1.1722 0.0112311 -0.0137437 0.002665 0.0232953 0.123497 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 71 121 -3.33955e-13 -3.05972 -0.0937068 0.0612327 -4.88498e-15 -3.73035e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 121 122 1.17974 0.0116801 -0.0139211 0.00267399 0.0234462 0.123468 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 72 122 -3.36176e-13 -3.05972 -0.0937068 0.0612327 -4.88498e-15 -3.73035e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 122 123 1.18728 0.0121288 -0.0140997 0.00268298 0.023597 0.12344 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 73 123 -3.3884e-13 -3.05972 -0.0937068 0.0612327 -4.88498e-15 -3.73035e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 123 124 1.19481 0.0125769 -0.0142793 0.00269195 0.0237477 0.123411 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 74 124 -3.40727e-13 -3.05972 -0.0937068 0.0612327 -4.88498e-15 -3.73035e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 124 125 1.20234 0.0130247 -0.0144601 0.00270092 0.0238985 0.123382 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 75 125 -3.42982e-13 -3.05972 -0.0937068 0.0612327 -4.88498e-15 -3.73035e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 125 126 1.20987 0.013472 -0.0146419 0.00270988 0.0240492 0.123353 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 76 126 -3.45168e-13 -3.05972 -0.0937068 0.0612327 -4.88498e-15 -3.73035e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 126 127 1.2174 0.0139188 -0.0148248 0.00271883 0.0241998 0.123324 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 77 127 -3.46834e-13 -3.05972 -0.0937068 0.0612327 -4.88498e-15 -3.73035e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 127 128 1.22493 0.0143652 -0.0150089 0.00272777 0.0243505 0.123294 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 78 128 -3.49054e-13 -3.05972 -0.0937068 0.0612327 -4.88498e-15 -3.73035e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 128 129 1.23246 0.0148111 -0.015194 0.0027367 0.0245011 0.123264 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 79 129 -3.52163e-13 -3.05972 -0.0937068 0.0612327 -5.32907e-15 -3.73035e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 129 130 1.23998 0.0152566 -0.0153802 0.00274562 0.0246516 0.123235 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 80 130 -3.53051e-13 -3.05972 -0.0937068 0.0612327 -5.32907e-15 -3.73035e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 130 131 1.2475 0.0157017 -0.0155675 0.00275453 0.0248021 0.123204 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 81 131 -3.55715e-13 -3.05972 -0.0937068 0.0612327 -5.32907e-15 -3.73035e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 131 132 1.25502 0.0161462 -0.0157559 0.00276344 0.0249526 0.123174 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 82 132 -3.57936e-13 -3.05972 -0.0937068 0.0612327 -5.32907e-15 -3.73035e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 132 133 1.26254 0.0165903 -0.0159454 0.00277233 0.0251031 0.123144 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 83 133 -3.60156e-13 -3.05972 -0.0937068 0.0612327 -5.32907e-15 -3.73035e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 133 134 1.27006 0.017034 -0.0161359 0.00278122 0.0252535 0.123113 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 84 134 -3.62377e-13 -3.05972 -0.0937068 0.0612327 -5.32907e-15 -3.73035e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 134 135 1.27757 0.0174771 -0.0163276 0.0027901 0.0254038 0.123082 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 85 135 -3.65041e-13 -3.05972 -0.0937068 0.0612327 -5.32907e-15 -3.73035e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 135 136 1.28508 0.0179199 -0.0165203 0.00279897 0.0255542 0.123051 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 86 136 -3.66596e-13 -3.05972 -0.0937068 0.0612327 -5.32907e-15 -3.73035e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 136 137 1.29259 0.0183621 -0.0167141 0.00280782 0.0257045 0.12302 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 87 137 -3.68816e-13 -3.05972 -0.0937068 0.0612327 -5.32907e-15 -3.73035e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 137 138 1.3001 0.0188038 -0.016909 0.00281667 0.0258547 0.122989 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 88 138 -3.70981e-13 -3.05972 -0.0937068 0.0612327 -5.32907e-15 -3.73035e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 138 139 1.30761 0.0192451 -0.017105 0.00282551 0.026005 0.122957 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 89 139 -3.73035e-13 -3.05972 -0.0937068 0.0612327 -5.77316e-15 -3.73035e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 139 140 1.31511 0.0196859 -0.0173021 0.00283434 0.0261551 0.122926 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 90 140 -3.75255e-13 -3.05972 -0.0937068 0.0612327 -5.77316e-15 -3.73035e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 140 141 1.32261 0.0201262 -0.0175002 0.00284316 0.0263053 0.122894 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 91 141 -3.76588e-13 -3.05972 -0.0937068 0.0612327 -5.77316e-15 -3.73035e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 141 142 1.33012 0.020566 -0.0176994 0.00285197 0.0264554 0.122862 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 92 142 -3.79696e-13 -3.05972 -0.0937068 0.0612327 -5.77316e-15 -3.73035e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 142 143 1.33761 0.0210054 -0.0178997 0.00286077 0.0266055 0.122829 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 93 143 -3.82805e-13 -3.05972 -0.0937068 0.0612327 -5.77316e-15 -3.73035e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 143 144 1.34511 0.0214442 -0.0181011 0.00286957 0.0267555 0.122797 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 94 144 -3.84581e-13 -3.05972 -0.0937068 0.0612327 -5.77316e-15 -3.68594e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 144 145 1.35261 0.0218826 -0.0183036 0.00287835 0.0269055 0.122764 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 95 145 -3.85469e-13 -3.05972 -0.0937068 0.0612327 -5.77316e-15 -3.73035e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 145 146 1.3601 0.0223204 -0.0185071 0.00288712 0.0270554 0.122732 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 96 146 -3.8769e-13 -3.05972 -0.0937068 0.0612327 -5.77316e-15 -3.73035e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 146 147 1.36759 0.0227578 -0.0187117 0.00289588 0.0272053 0.122699 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 97 147 -3.90354e-13 -3.05972 -0.0937068 0.0612327 -5.77316e-15 -3.68594e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 147 148 1.37508 0.0231946 -0.0189173 0.00290463 0.0273552 0.122665 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 98 148 -3.91909e-13 -3.05972 -0.0937068 0.0612327 -5.77316e-15 -3.73035e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 148 149 1.38256 0.0236309 -0.0191241 0.00291338 0.027505 0.122632 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 99 149 -3.94462e-13 -3.05972 -0.0937068 0.0612327 -6.21725e-15 -3.68594e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 149 150 1.39005 0.0240668 -0.0193319 0.00292211 0.0276548 0.122599 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 100 150 -3.96557e-13 -3.05972 -0.0937068 0.0612327 -6.21725e-15 -3.68594e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 150 151 1.39753 0.0245021 -0.0195407 0.00293083 0.0278045 0.122565 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 101 151 -3.98348e-13 -3.05972 -0.0937068 0.0612327 -6.21725e-15 -3.68594e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 151 152 1.40501 0.0249369 -0.0197507 0.00293954 0.0279542 0.122531 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 102 152 -4.00568e-13 -3.05972 -0.0937068 0.0612327 -6.21725e-15 -3.68594e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 152 153 1.41249 0.0253712 -0.0199617 0.00294824 0.0281039 0.122497 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 103 153 -4.03233e-13 -3.05972 -0.0937068 0.0612327 -6.21725e-15 -3.68594e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 153 154 1.41996 0.025805 -0.0201737 0.00295694 0.0282535 0.122463 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 104 154 -4.05009e-13 -3.05972 -0.0937068 0.0612327 -6.21725e-15 -3.73035e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 154 155 1.42744 0.0262382 -0.0203868 0.00296562 0.0284031 0.122428 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 105 155 -4.07674e-13 -3.05972 -0.0937068 0.0612327 -6.21725e-15 -3.68594e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 155 156 1.43491 0.026671 -0.020601 0.00297429 0.0285526 0.122394 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 106 156 -4.08562e-13 -3.05972 -0.0937068 0.0612327 -6.21725e-15 -3.68594e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 156 157 1.44238 0.0271032 -0.0208163 0.00298295 0.0287021 0.122359 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 107 157 -4.11227e-13 -3.05972 -0.0937068 0.0612327 -6.21725e-15 -3.68594e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 157 158 1.44985 0.0275349 -0.0210326 0.0029916 0.0288516 0.122324 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 108 158 -4.13003e-13 -3.05972 -0.0937068 0.0612327 -6.21725e-15 -3.68594e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 158 159 1.45731 0.027966 -0.0212499 0.00300024 0.029001 0.122289 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 109 159 -4.16112e-13 -3.05972 -0.0937068 0.0612327 -6.66134e-15 -3.68594e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 159 160 1.46477 0.0283966 -0.0214683 0.00300887 0.0291504 0.122253 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 110 160 -4.17888e-13 -3.05972 -0.0937068 0.0612327 -6.66134e-15 -3.68594e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 160 161 1.47224 0.0288267 -0.0216878 0.00301748 0.0292997 0.122218 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 111 161 -4.2033e-13 -3.05972 -0.0937068 0.0612327 -6.66134e-15 -3.68594e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 161 162 1.47969 0.0292562 -0.0219083 0.00302609 0.029449 0.122182 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 112 162 -4.22107e-13 -3.05972 -0.0937068 0.0612327 -6.66134e-15 -3.68594e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 162 163 1.48715 0.0296852 -0.0221299 0.00303469 0.0295982 0.122146 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 113 163 -4.24216e-13 -3.05972 -0.0937068 0.0612327 -6.66134e-15 -3.68594e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 163 164 1.4946 0.0301137 -0.0223525 0.00304328 0.0297474 0.12211 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 114 164 -4.2677e-13 -3.05972 -0.0937068 0.0612327 -6.66134e-15 -3.68594e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 164 165 1.50206 0.0305416 -0.0225762 0.00305185 0.0298965 0.122074 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 115 165 -4.23661e-13 -3.05972 -0.0937068 0.0612327 -6.21725e-15 -3.5083e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 165 166 1.50951 0.030969 -0.0228009 0.00306042 0.0300457 0.122037 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 116 166 -4.24549e-13 -3.05972 -0.0937068 0.0612327 -6.66134e-15 -3.5083e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 166 167 1.51695 0.0313958 -0.0230266 0.00306897 0.0301947 0.122001 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 117 167 -4.26326e-13 -3.05972 -0.0937068 0.0612327 -6.66134e-15 -3.5083e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 167 168 1.5244 0.031822 -0.0232535 0.00307751 0.0303437 0.121964 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 118 168 -4.2899e-13 -3.05972 -0.0937068 0.0612327 -6.66134e-15 -3.5083e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 168 169 1.53184 0.0322477 -0.0234813 0.00308604 0.0304927 0.121927 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 119 169 -4.31655e-13 -3.05972 -0.0937068 0.0612327 -6.66134e-15 -3.5083e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 169 170 1.53928 0.0326729 -0.0237102 0.00309457 0.0306416 0.12189 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 120 170 -4.33431e-13 -3.05972 -0.0937068 0.0612327 -6.66134e-15 -3.5083e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 170 171 1.54672 0.0330974 -0.0239401 0.00310308 0.0307905 0.121852 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 121 171 -4.36984e-13 -3.05972 -0.0937068 0.0612327 -6.66134e-15 -3.5083e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 171 172 1.55416 0.0335214 -0.0241711 0.00311157 0.0309393 0.121815 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 122 172 -4.3876e-13 -3.05972 -0.0937068 0.0612327 -6.66134e-15 -3.5083e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 172 173 1.56159 0.0339449 -0.0244031 0.00312006 0.0310881 0.121777 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 123 173 -4.39648e-13 -3.05972 -0.0937068 0.0612327 -6.66134e-15 -3.5083e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 173 174 1.56902 0.0343678 -0.0246362 0.00312854 0.0312369 0.121739 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 124 174 -4.42313e-13 -3.05972 -0.0937068 0.0612327 -6.66134e-15 -3.5083e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 174 175 1.57645 0.0347901 -0.0248702 0.003137 0.0313856 0.121701 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 125 175 -4.44458e-13 -3.05972 -0.0937068 0.0612327 -6.66134e-15 -3.5083e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 175 176 1.58388 0.0352118 -0.0251053 0.00314546 0.0315342 0.121663 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 126 176 -4.46532e-13 -3.05972 -0.0937068 0.0612327 -7.10543e-15 -3.5083e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 176 177 1.5913 0.0356329 -0.0253415 0.0031539 0.0316828 0.121625 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 127 177 -4.48974e-13 -3.05972 -0.0937068 0.0612327 -7.10543e-15 -3.5083e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 177 178 1.59872 0.0360535 -0.0255787 0.00316233 0.0318314 0.121586 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 128 178 -4.51195e-13 -3.05972 -0.0937068 0.0612327 -7.10543e-15 -3.5083e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 178 179 1.60614 0.0364735 -0.0258169 0.00317075 0.0319799 0.121547 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 129 179 -4.52971e-13 -3.05972 -0.0937068 0.0612327 -7.10543e-15 -3.5083e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 179 180 1.61356 0.0368929 -0.0260561 0.00317915 0.0321284 0.121508 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 130 180 -4.54747e-13 -3.05972 -0.0937068 0.0612327 -7.10543e-15 -3.5083e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 180 181 1.62097 0.0373117 -0.0262964 0.00318755 0.0322768 0.121469 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 131 181 -4.583e-13 -3.05972 -0.0937068 0.0612327 -7.10543e-15 -3.5083e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 181 182 1.62839 0.0377299 -0.0265377 0.00319594 0.0324251 0.12143 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 132 182 -4.60965e-13 -3.05972 -0.0937068 0.0612327 -7.10543e-15 -3.5083e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 182 183 1.63579 0.0381476 -0.02678 0.00320431 0.0325735 0.12139 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 133 183 -4.62741e-13 -3.05972 -0.0937068 0.0612327 -7.10543e-15 -3.5083e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 183 184 1.6432 0.0385646 -0.0270233 0.00321267 0.0327217 0.12135 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 134 184 -4.64073e-13 -3.05972 -0.0937068 0.0612327 -7.10543e-15 -3.5083e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 184 185 1.65061 0.0389811 -0.0272677 0.00322102 0.03287 0.121311 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 135 185 -4.64961e-13 -3.05972 -0.0937068 0.0612327 -7.10543e-15 -3.5083e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 185 186 1.65801 0.0393969 -0.027513 0.00322935 0.0330181 0.12127 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 136 186 -4.67182e-13 -3.05972 -0.0937068 0.0612327 -7.10543e-15 -3.5083e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 186 187 1.66541 0.0398121 -0.0277594 0.00323768 0.0331663 0.12123 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 137 187 -4.69735e-13 -3.05972 -0.0937068 0.0612327 -7.54952e-15 -3.5083e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 187 188 1.67281 0.0402268 -0.0280068 0.00324599 0.0333143 0.12119 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 138 188 -4.71845e-13 -3.05972 -0.0937068 0.0612327 -7.54952e-15 -3.5083e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 188 189 1.6802 0.0406408 -0.0282552 0.00325429 0.0334624 0.121149 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 139 189 -4.73621e-13 -3.05972 -0.0937068 0.0612327 -7.54952e-15 -3.5083e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 189 190 1.68759 0.0410542 -0.0285047 0.00326258 0.0336103 0.121108 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 140 190 -4.7562e-13 -3.05972 -0.0937068 0.0612327 -7.54952e-15 -3.5083e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 190 191 1.69498 0.041467 -0.0287551 0.00327086 0.0337583 0.121067 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 141 191 -4.78728e-13 -3.05972 -0.0937068 0.0612327 -7.54952e-15 -3.5083e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 191 192 1.70237 0.0418792 -0.0290066 0.00327913 0.0339062 0.121026 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 142 192 -4.80505e-13 -3.05972 -0.0937068 0.0612327 -7.54952e-15 -3.5083e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 192 193 1.70975 0.0422908 -0.0292591 0.00328738 0.034054 0.120985 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 143 193 -4.82281e-13 -3.05972 -0.0937068 0.0612327 -7.54952e-15 -3.5083e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 193 194 1.71714 0.0427018 -0.0295125 0.00329562 0.0342018 0.120943 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 144 194 -4.83169e-13 -3.05972 -0.0937068 0.0612327 -7.54952e-15 -3.5083e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 194 195 1.72452 0.0431121 -0.029767 0.00330385 0.0343495 0.120902 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 145 195 -4.8761e-13 -3.05972 -0.0937068 0.0612327 -7.54952e-15 -3.5083e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 195 196 1.73189 0.0435218 -0.0300225 0.00331206 0.0344972 0.12086 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 146 196 -4.89386e-13 -3.05972 -0.0937068 0.0612327 -7.99361e-15 -3.5083e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 196 197 1.73927 0.0439309 -0.030279 0.00332027 0.0346448 0.120818 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 147 197 -4.90274e-13 -3.05972 -0.0937068 0.0612327 -7.99361e-15 -3.5083e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 197 198 1.74664 0.0443393 -0.0305365 0.00332846 0.0347924 0.120776 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 148 198 -4.93383e-13 -3.05972 -0.0937068 0.0612327 -7.99361e-15 -3.5083e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 198 199 1.75401 0.0447471 -0.0307949 0.00333664 0.0349399 0.120733 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 149 199 -4.94937e-13 -3.05972 -0.0937068 0.0612327 -7.99361e-15 -3.5083e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 199 200 1.76137 0.0451543 -0.0310544 0.0033448 0.0350874 0.120691 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 150 200 -4.97279e-13 -3.05972 -0.0937068 0.0612327 -7.99361e-15 -3.5083e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 200 201 1.76874 0.0455609 -0.0313149 0.00335296 0.0352348 0.120648 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 151 201 -4.99822e-13 -3.05972 -0.0937068 0.0612327 -7.99361e-15 -3.5083e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 201 202 1.7761 0.0459668 -0.0315764 0.0033611 0.0353821 0.120605 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 152 202 -5.02265e-13 -3.05972 -0.0937068 0.0612327 -7.99361e-15 -3.4639e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 202 203 1.78346 0.0463721 -0.0318389 0.00336922 0.0355295 0.120562 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 153 203 -5.02709e-13 -3.05972 -0.0937068 0.0612327 -7.99361e-15 -3.4639e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 203 204 1.79081 0.0467767 -0.0321023 0.00337734 0.0356767 0.120518 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 154 204 -5.05374e-13 -3.05972 -0.0937068 0.0612327 -7.99361e-15 -3.4639e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 204 205 1.79817 0.0471807 -0.0323668 0.00338544 0.0358239 0.120475 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 155 205 -5.0715e-13 -3.05972 -0.0937068 0.0612327 -7.99361e-15 -3.5083e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 205 206 1.80552 0.047584 -0.0326322 0.00339353 0.0359711 0.120431 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 156 206 -5.10703e-13 -3.05972 -0.0937068 0.0612327 -7.99361e-15 -3.4639e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 206 207 1.81286 0.0479867 -0.0328986 0.00340161 0.0361182 0.120388 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 157 207 -5.12479e-13 -3.05972 -0.0937068 0.0612327 -8.43769e-15 -3.4639e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 207 208 1.82021 0.0483887 -0.0331661 0.00340967 0.0362652 0.120343 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 158 208 -5.13367e-13 -3.05972 -0.0937068 0.0612327 -8.43769e-15 -3.4639e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 208 209 1.82755 0.0487901 -0.0334345 0.00341772 0.0364122 0.120299 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 159 209 -5.1692e-13 -3.05972 -0.0937068 0.0612327 -8.43769e-15 -3.4639e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 209 210 1.83489 0.0491908 -0.0337038 0.00342576 0.0365592 0.120255 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 160 210 -5.17808e-13 -3.05972 -0.0937068 0.0612327 -8.43769e-15 -3.4639e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 210 211 1.84223 0.0495908 -0.0339742 0.00343379 0.0367061 0.12021 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 161 211 -5.20028e-13 -3.05972 -0.0937068 0.0612327 -8.43769e-15 -3.4639e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 211 212 1.84956 0.0499902 -0.0342455 0.0034418 0.0368529 0.120166 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 162 212 -5.22471e-13 -3.05972 -0.0937068 0.0612327 -8.43769e-15 -3.4639e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 212 213 1.85689 0.0503889 -0.0345178 0.0034498 0.0369997 0.120121 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 163 213 -5.24802e-13 -3.05972 -0.0937068 0.0612327 -8.43769e-15 -3.4639e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 213 214 1.86422 0.050787 -0.0347911 0.00345778 0.0371464 0.120076 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 164 214 -5.2669e-13 -3.05972 -0.0937068 0.0612327 -8.43769e-15 -3.4639e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 214 215 1.87155 0.0511843 -0.0350654 0.00346575 0.0372931 0.12003 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 165 215 -5.28466e-13 -3.05972 -0.0937068 0.0612327 -8.43769e-15 -3.4639e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 215 216 1.87887 0.0515811 -0.0353406 0.00347371 0.0374397 0.119985 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 166 216 -5.31131e-13 -3.05972 -0.0937068 0.0612327 -8.43769e-15 -3.4639e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 216 217 1.88619 0.0519771 -0.0356169 0.00348166 0.0375863 0.119939 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 167 217 -5.33795e-13 -3.05972 -0.0937068 0.0612327 -8.88178e-15 -3.4639e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 217 218 1.89351 0.0523724 -0.035894 0.00348959 0.0377328 0.119893 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 168 218 -5.33795e-13 -3.05972 -0.0937068 0.0612327 -8.88178e-15 -3.4639e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 218 219 1.90082 0.0527671 -0.0361722 0.00349751 0.0378792 0.119847 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 169 219 -5.35572e-13 -3.05972 -0.0937068 0.0612327 -8.88178e-15 -3.4639e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 219 220 1.90813 0.0531611 -0.0364513 0.00350541 0.0380256 0.119801 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 170 220 -5.40901e-13 -3.05972 -0.0937068 0.0612327 -8.88178e-15 -3.4639e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 220 221 1.91544 0.0535544 -0.0367314 0.00351331 0.0381719 0.119755 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 171 221 -5.40901e-13 -3.05972 -0.0937068 0.0612327 -8.88178e-15 -3.4639e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 221 222 1.92275 0.053947 -0.0370124 0.00352118 0.0383182 0.119708 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 172 222 -5.41789e-13 -3.05972 -0.0937068 0.0612327 -8.88178e-15 -3.4639e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 222 223 1.93005 0.054339 -0.0372944 0.00352905 0.0384644 0.119662 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 173 223 -5.4623e-13 -3.05972 -0.0937068 0.0612327 -8.88178e-15 -3.4639e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 223 224 1.93735 0.0547302 -0.0375774 0.0035369 0.0386106 0.119615 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 174 224 -5.48006e-13 -3.05972 -0.0937068 0.0612327 -8.88178e-15 -3.4639e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 224 225 1.94465 0.0551207 -0.0378613 0.00354473 0.0387567 0.119568 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 175 225 -5.49634e-13 -3.05972 -0.0937068 0.0612327 -8.88178e-15 -3.4639e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 225 226 1.95194 0.0555106 -0.0381461 0.00355256 0.0389028 0.119521 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 176 226 -5.51559e-13 -3.05972 -0.0937068 0.0612327 -8.88178e-15 -3.4639e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 226 227 1.95923 0.0558997 -0.038432 0.00356037 0.0390488 0.119473 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 177 227 -5.53335e-13 -3.05972 -0.0937068 0.0612327 -8.88178e-15 -3.4639e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 227 228 1.96652 0.0562882 -0.0387188 0.00356816 0.0391947 0.119426 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 178 228 -5.56e-13 -3.05972 -0.0937068 0.0612327 -9.32587e-15 -3.4639e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 228 229 1.97381 0.0566759 -0.0390065 0.00357594 0.0393406 0.119378 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 179 229 -5.59552e-13 -3.05972 -0.0937068 0.0612327 -9.32587e-15 -3.4639e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 229 230 1.98109 0.057063 -0.0392952 0.00358371 0.0394864 0.11933 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 180 230 -5.60441e-13 -3.05972 -0.0937068 0.0612327 -9.32587e-15 -3.4639e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 230 231 1.98837 0.0574493 -0.0395848 0.00359146 0.0396322 0.119282 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 181 231 -5.62217e-13 -3.05972 -0.0937068 0.0612327 -9.32587e-15 -3.4639e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 231 232 1.99565 0.0578349 -0.0398754 0.0035992 0.0397779 0.119233 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 182 232 -5.63993e-13 -3.05972 -0.0937068 0.0612327 -9.32587e-15 -3.4639e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 232 233 2.00292 0.0582198 -0.0401669 0.00360693 0.0399235 0.119185 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 183 233 -5.64881e-13 -3.05972 -0.0937068 0.0612327 -9.32587e-15 -3.4639e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 233 234 2.01019 0.058604 -0.0404593 0.00361464 0.0400691 0.119136 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 184 234 -5.68434e-13 -3.05972 -0.0937068 0.0612327 -9.32587e-15 -3.4639e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 234 235 2.01746 0.0589875 -0.0407527 0.00362234 0.0402146 0.119087 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 185 235 -5.69766e-13 -3.05972 -0.0937068 0.0612327 -9.32587e-15 -3.4639e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 235 236 2.02472 0.0593702 -0.041047 0.00363002 0.0403601 0.119038 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 186 236 -5.72875e-13 -3.05972 -0.0937068 0.0612327 -9.32587e-15 -3.4639e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 236 237 2.03198 0.0597523 -0.0413423 0.00363769 0.0405055 0.118989 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 187 237 -5.74651e-13 -3.05972 -0.0937068 0.0612327 -9.32587e-15 -3.4639e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 237 238 2.03924 0.0601336 -0.0416385 0.00364534 0.0406508 0.11894 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 188 238 -5.76539e-13 -3.05972 -0.0937068 0.0612327 -9.76996e-15 -3.4639e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 238 239 2.0465 0.0605142 -0.0419357 0.00365298 0.0407961 0.11889 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 189 239 -5.78204e-13 -3.05972 -0.0937068 0.0612327 -9.76996e-15 -3.4639e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 239 240 2.05375 0.060894 -0.0422337 0.00366061 0.0409414 0.118841 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 190 240 -5.81313e-13 -3.05972 -0.0937068 0.0612327 -9.76996e-15 -3.4639e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 240 241 2.061 0.0612731 -0.0425327 0.00366822 0.0410865 0.118791 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 191 241 -5.82645e-13 -3.05972 -0.0937068 0.0612327 -9.76996e-15 -3.4639e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 241 242 2.06824 0.0616515 -0.0428327 0.00367581 0.0412316 0.118741 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 192 242 -5.84421e-13 -3.05972 -0.0937068 0.0612327 -9.76996e-15 -3.4639e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 242 243 2.07549 0.0620292 -0.0431335 0.0036834 0.0413767 0.11869 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 193 243 -5.8531e-13 -3.05972 -0.0937068 0.0612327 -9.76996e-15 -3.4639e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 243 244 2.08273 0.0624061 -0.0434353 0.00369096 0.0415217 0.11864 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 194 244 -5.8975e-13 -3.05972 -0.0937068 0.0612327 -9.76996e-15 -3.4639e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 244 245 2.08996 0.0627822 -0.043738 0.00369851 0.0416666 0.118589 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 195 245 -5.91527e-13 -3.05972 -0.0937068 0.0612327 -9.76996e-15 -3.41949e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 245 246 2.0972 0.0631577 -0.0440416 0.00370605 0.0418114 0.118538 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 196 246 -5.93303e-13 -3.05972 -0.0937068 0.0612327 -9.76996e-15 -3.41949e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 246 247 2.10443 0.0635324 -0.0443461 0.00371357 0.0419562 0.118488 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 197 247 -5.9508e-13 -3.05972 -0.0937068 0.0612327 -9.76996e-15 -3.41949e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 247 248 2.11165 0.0639063 -0.0446516 0.00372108 0.042101 0.118436 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 198 248 -5.98188e-13 -3.05972 -0.0937068 0.0612327 -9.76996e-15 -3.41949e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 248 249 2.11888 0.0642795 -0.044958 0.00372858 0.0422456 0.118385 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 199 249 -5.99298e-13 -3.05972 -0.0937068 0.0612327 -1.02141e-14 -3.41949e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 249 250 2.1261 0.0646519 -0.0452653 0.00373605 0.0423903 0.118334 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 200 250 -6.01474e-13 -3.05972 -0.0937068 0.0612327 -1.02141e-14 -3.41949e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 250 251 2.13332 0.0650236 -0.0455734 0.00374352 0.0425348 0.118282 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 201 251 -6.03295e-13 -3.05972 -0.0937068 0.0612327 -1.02141e-14 -3.41949e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 251 252 2.14053 0.0653945 -0.0458826 0.00375097 0.0426793 0.11823 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 202 252 -6.05294e-13 -3.05972 -0.0937068 0.0612327 -1.02141e-14 -3.41949e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 252 253 2.14774 0.0657647 -0.0461926 0.0037584 0.0428237 0.118178 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 203 253 -6.07514e-13 -3.05972 -0.0937068 0.0612327 -1.02141e-14 -3.41949e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 253 254 2.15495 0.0661341 -0.0465035 0.00376582 0.0429681 0.118126 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 204 254 -6.08402e-13 -3.05972 -0.0937068 0.0612327 -1.02141e-14 -3.41949e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 254 255 2.16216 0.0665028 -0.0468153 0.00377322 0.0431124 0.118073 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 205 255 -5.48894e-13 -3.05972 -0.0937068 0.0612327 -8.43769e-15 -2.75335e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 255 256 2.16936 0.0668706 -0.047128 0.00378061 0.0432566 0.118021 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 206 256 -5.53335e-13 -3.05972 -0.0937068 0.0612327 -8.43769e-15 -2.75335e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 256 257 2.17656 0.0672378 -0.0474416 0.00378798 0.0434008 0.117968 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 207 257 -5.55112e-13 -3.05972 -0.0937068 0.0612327 -8.43769e-15 -2.75335e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 257 258 2.18375 0.0676041 -0.0477562 0.00379534 0.0435449 0.117915 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 208 258 -5.56888e-13 -3.05972 -0.0937068 0.0612327 -8.43769e-15 -2.75335e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 258 259 2.19094 0.0679697 -0.0480716 0.00380268 0.0436889 0.117862 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 209 259 -5.57776e-13 -3.05972 -0.0937068 0.0612327 -8.43769e-15 -2.75335e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 259 260 2.19813 0.0683345 -0.0483879 0.00381001 0.0438329 0.117809 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 210 260 -5.58664e-13 -3.05972 -0.0937068 0.0612327 -8.43769e-15 -2.75335e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 260 261 2.20532 0.0686985 -0.0487051 0.00381732 0.0439768 0.117755 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 211 261 -5.61329e-13 -3.05972 -0.0937068 0.0612327 -8.43769e-15 -2.75335e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 261 262 2.2125 0.0690618 -0.0490232 0.00382462 0.0441206 0.117702 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 212 262 -5.63549e-13 -3.05972 -0.0937068 0.0612327 -8.43769e-15 -2.75335e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 262 263 2.21968 0.0694242 -0.0493422 0.0038319 0.0442644 0.117648 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 213 263 -5.65215e-13 -3.05972 -0.0937068 0.0612327 -8.43769e-15 -2.75335e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 263 264 2.22685 0.0697859 -0.0496621 0.00383916 0.0444081 0.117594 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 214 264 -5.67102e-13 -3.05972 -0.0937068 0.0612327 -8.43769e-15 -2.75335e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 264 265 2.23402 0.0701468 -0.0499828 0.00384641 0.0445518 0.11754 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 215 265 -5.69322e-13 -3.05972 -0.0937068 0.0612327 -8.43769e-15 -2.75335e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 265 266 2.24119 0.0705069 -0.0503044 0.00385365 0.0446954 0.117486 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 216 266 -5.71099e-13 -3.05972 -0.0937068 0.0612327 -8.43769e-15 -2.75335e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 266 267 2.24836 0.0708662 -0.050627 0.00386087 0.0448389 0.117431 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 217 267 -5.71099e-13 -3.05972 -0.0937068 0.0612327 -8.43769e-15 -2.75335e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 267 268 2.25552 0.0712248 -0.0509504 0.00386807 0.0449823 0.117377 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 218 268 -5.76428e-13 -3.05972 -0.0937068 0.0612327 -8.43769e-15 -2.70894e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 268 269 2.26268 0.0715825 -0.0512746 0.00387526 0.0451257 0.117322 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 219 269 -5.76428e-13 -3.05972 -0.0937068 0.0612327 -8.88178e-15 -2.75335e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 269 270 2.26983 0.0719395 -0.0515998 0.00388243 0.045269 0.117267 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 220 270 -5.76428e-13 -3.05972 -0.0937068 0.0612327 -8.88178e-15 -2.75335e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 270 271 2.27698 0.0722956 -0.0519258 0.00388958 0.0454123 0.117212 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 221 271 -5.79092e-13 -3.05972 -0.0937068 0.0612327 -8.88178e-15 -2.70894e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 271 272 2.28413 0.0726509 -0.0522527 0.00389672 0.0455554 0.117156 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 222 272 -5.82645e-13 -3.05972 -0.0937068 0.0612327 -8.88178e-15 -2.75335e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 272 273 2.29128 0.0730055 -0.0525805 0.00390385 0.0456986 0.117101 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 223 273 -5.83089e-13 -3.05972 -0.0937068 0.0612327 -8.88178e-15 -2.70894e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 273 274 2.29842 0.0733592 -0.0529091 0.00391095 0.0458416 0.117045 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 224 274 -5.86198e-13 -3.05972 -0.0937068 0.0612327 -8.88178e-15 -2.70894e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 274 275 2.30556 0.0737122 -0.0532386 0.00391805 0.0459846 0.116989 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 225 275 -5.87397e-13 -3.05972 -0.0937068 0.0612327 -8.88178e-15 -2.70894e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 275 276 2.31269 0.0740643 -0.053569 0.00392512 0.0461275 0.116933 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 226 276 -5.89306e-13 -3.05972 -0.0937068 0.0612327 -8.88178e-15 -2.70894e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 276 277 2.31982 0.0744156 -0.0539002 0.00393218 0.0462703 0.116877 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 227 277 -5.91083e-13 -3.05972 -0.0937068 0.0612327 -8.88178e-15 -2.70894e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 277 278 2.32695 0.0747661 -0.0542323 0.00393923 0.0464131 0.11682 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 228 278 -5.92415e-13 -3.05972 -0.0937068 0.0612327 -8.88178e-15 -2.70894e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 278 279 2.33407 0.0751158 -0.0545652 0.00394625 0.0465558 0.116764 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 229 279 -5.95968e-13 -3.05972 -0.0937068 0.0612327 -8.88178e-15 -2.70894e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 279 280 2.34119 0.0754647 -0.054899 0.00395326 0.0466985 0.116707 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 230 280 -5.97744e-13 -3.05972 -0.0937068 0.0612327 -8.88178e-15 -2.70894e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 280 281 2.34831 0.0758127 -0.0552337 0.00396026 0.046841 0.11665 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 231 281 -5.95968e-13 -3.05972 -0.0937068 0.0612327 -8.88178e-15 -2.70894e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 281 282 2.35543 0.07616 -0.0555692 0.00396724 0.0469835 0.116593 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 232 282 -6.00409e-13 -3.05972 -0.0937068 0.0612327 -8.88178e-15 -2.70894e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 282 283 2.36254 0.0765064 -0.0559055 0.0039742 0.0471259 0.116536 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 233 283 -6.02185e-13 -3.05972 -0.0937068 0.0612327 -9.32587e-15 -2.70894e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 283 284 2.36964 0.076852 -0.0562427 0.00398115 0.0472683 0.116478 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 234 284 -6.03961e-13 -3.05972 -0.0937068 0.0612327 -9.32587e-15 -2.70894e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 284 285 2.37674 0.0771967 -0.0565808 0.00398808 0.0474106 0.116421 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 235 285 -6.05738e-13 -3.05972 -0.0937068 0.0612327 -9.32587e-15 -2.70894e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 285 286 2.38384 0.0775407 -0.0569196 0.00399499 0.0475528 0.116363 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 236 286 -6.07958e-13 -3.05972 -0.0937068 0.0612327 -9.32587e-15 -2.70894e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 286 287 2.39094 0.0778838 -0.0572594 0.00400189 0.047695 0.116305 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 237 287 -6.0929e-13 -3.05972 -0.0937068 0.0612327 -9.32587e-15 -2.70894e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 287 288 2.39803 0.078226 -0.0575999 0.00400877 0.047837 0.116247 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 238 288 -6.11067e-13 -3.05972 -0.0937068 0.0612327 -9.32587e-15 -2.70894e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 288 289 2.40512 0.0785675 -0.0579413 0.00401563 0.047979 0.116188 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 239 289 -6.13287e-13 -3.05972 -0.0937068 0.0612327 -9.32587e-15 -2.70894e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 289 290 2.41221 0.0789081 -0.0582836 0.00402248 0.048121 0.11613 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 240 290 -6.15508e-13 -3.05972 -0.0937068 0.0612327 -9.32587e-15 -2.70894e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 290 291 2.41929 0.0792478 -0.0586267 0.00402931 0.0482628 0.116071 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 241 291 -6.17284e-13 -3.05972 -0.0937068 0.0612327 -9.32587e-15 -2.70894e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 291 292 2.42636 0.0795867 -0.0589706 0.00403612 0.0484046 0.116012 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 242 292 -6.18172e-13 -3.05972 -0.0937068 0.0612327 -9.32587e-15 -2.70894e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 292 293 2.43344 0.0799248 -0.0593153 0.00404292 0.0485464 0.115953 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 243 293 -6.21725e-13 -3.05972 -0.0937068 0.0612327 -9.32587e-15 -2.70894e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 293 294 2.44051 0.080262 -0.0596608 0.0040497 0.048688 0.115894 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 244 294 -6.23501e-13 -3.05972 -0.0937068 0.0612327 -9.76996e-15 -2.70894e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 294 295 2.44758 0.0805984 -0.0600072 0.00405647 0.0488296 0.115835 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 245 295 -6.23501e-13 -3.05972 -0.0937068 0.0612327 -9.76996e-15 -2.70894e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 295 296 2.45464 0.0809339 -0.0603544 0.00406321 0.0489711 0.115775 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 246 296 -6.25278e-13 -3.05972 -0.0937068 0.0612327 -9.76996e-15 -2.70894e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 296 297 2.4617 0.0812686 -0.0607025 0.00406994 0.0491125 0.115716 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 247 297 -6.29718e-13 -3.05972 -0.0937068 0.0612327 -9.76996e-15 -2.70894e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 297 298 2.46875 0.0816024 -0.0610513 0.00407665 0.0492539 0.115656 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 248 298 -6.29718e-13 -3.05972 -0.0937068 0.0612327 -9.76996e-15 -2.70894e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 298 299 2.47581 0.0819354 -0.061401 0.00408335 0.0493952 0.115596 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 249 299 -6.31495e-13 -3.05972 -0.0937068 0.0612327 -9.76996e-15 -2.70894e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 299 300 2.48285 0.0822675 -0.0617515 0.00409003 0.0495364 0.115535 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 250 300 -6.33035e-13 -3.05972 -0.0937068 0.0612327 -9.76996e-15 -2.70894e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 300 301 2.4899 0.0825988 -0.0621027 0.00409669 0.0496775 0.115475 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 251 301 -6.34603e-13 -3.05972 -0.0937068 0.0612327 -9.76996e-15 -2.70894e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 301 302 2.49694 0.0829292 -0.0624548 0.00410334 0.0498186 0.115415 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 252 302 -6.36824e-13 -3.05972 -0.0937068 0.0612327 -9.76996e-15 -2.70894e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 302 303 2.50398 0.0832587 -0.0628078 0.00410996 0.0499596 0.115354 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 253 303 -6.40377e-13 -3.05972 -0.0937068 0.0612327 -9.76996e-15 -2.66454e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 303 304 2.51101 0.0835873 -0.0631615 0.00411657 0.0501005 0.115293 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 254 304 -6.40377e-13 -3.05972 -0.0937068 0.0612327 -9.76996e-15 -2.70894e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 304 305 2.51804 0.0839151 -0.063516 0.00412317 0.0502413 0.115232 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 255 305 -7.24754e-13 -3.05972 -0.0937068 0.0612327 -1.24345e-14 -3.33067e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 305 306 2.52507 0.0842421 -0.0638713 0.00412974 0.0503821 0.115171 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 256 306 -7.24754e-13 -3.05972 -0.0937068 0.0612327 -1.24345e-14 -3.37508e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 306 307 2.53209 0.0845681 -0.0642274 0.0041363 0.0505228 0.115109 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 257 307 -7.2653e-13 -3.05972 -0.0937068 0.0612327 -1.24345e-14 -3.37508e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 307 308 2.53911 0.0848933 -0.0645844 0.00414284 0.0506634 0.115047 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 258 308 -7.28306e-13 -3.05972 -0.0937068 0.0612327 -1.24345e-14 -3.33067e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 308 309 2.54612 0.0852176 -0.0649421 0.00414937 0.050804 0.114986 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 259 309 -7.31859e-13 -3.05972 -0.0937068 0.0612327 -1.24345e-14 -3.37508e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 309 310 2.55313 0.085541 -0.0653006 0.00415588 0.0509444 0.114924 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 260 310 -7.32747e-13 -3.05972 -0.0937068 0.0612327 -1.24345e-14 -3.37508e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 310 311 2.56014 0.0858636 -0.0656599 0.00416236 0.0510848 0.114862 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 261 311 -7.34968e-13 -3.05972 -0.0937068 0.0612327 -1.24345e-14 -3.33067e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 311 312 2.56714 0.0861852 -0.06602 0.00416884 0.0512251 0.114799 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 262 312 -7.3741e-13 -3.05972 -0.0937068 0.0612327 -1.24345e-14 -3.33067e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 312 313 2.57414 0.086506 -0.0663808 0.00417529 0.0513654 0.114737 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 263 313 -7.39409e-13 -3.05972 -0.0937068 0.0612327 -1.28786e-14 -3.33067e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 313 314 2.58113 0.0868259 -0.0667425 0.00418173 0.0515056 0.114674 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 264 314 -7.41629e-13 -3.05972 -0.0937068 0.0612327 -1.28786e-14 -3.33067e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 314 315 2.58813 0.0871449 -0.0671049 0.00418815 0.0516456 0.114611 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 265 315 -7.42517e-13 -3.05972 -0.0937068 0.0612327 -1.28786e-14 -3.33067e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 315 316 2.59511 0.0874631 -0.0674682 0.00419455 0.0517857 0.114548 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 266 316 -7.4607e-13 -3.05972 -0.0937068 0.0612327 -1.28786e-14 -3.33067e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 316 317 2.6021 0.0877803 -0.0678322 0.00420093 0.0519256 0.114485 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 267 317 -7.4607e-13 -3.05972 -0.0937068 0.0612327 -1.28786e-14 -3.33067e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 317 318 2.60908 0.0880966 -0.0681969 0.0042073 0.0520655 0.114422 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 268 318 -7.47846e-13 -3.05972 -0.0937068 0.0612327 -1.28786e-14 -3.33067e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 318 319 2.61605 0.0884121 -0.0685625 0.00421365 0.0522052 0.114359 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 269 319 -7.53175e-13 -3.05972 -0.0937068 0.0612327 -1.28786e-14 -3.33067e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 319 320 2.62302 0.0887266 -0.0689288 0.00421998 0.0523449 0.114295 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 270 320 -7.54952e-13 -3.05972 -0.0937068 0.0612327 -1.28786e-14 -3.33067e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 320 321 2.62999 0.0890403 -0.0692959 0.00422629 0.0524846 0.114231 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 271 321 -7.56728e-13 -3.05972 -0.0937068 0.0612327 -1.28786e-14 -3.33067e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 321 322 2.63696 0.089353 -0.0696637 0.00423258 0.0526241 0.114167 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 272 322 -7.56728e-13 -3.05972 -0.0937068 0.0612327 -1.28786e-14 -3.33067e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 322 323 2.64392 0.0896649 -0.0700324 0.00423886 0.0527636 0.114103 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 273 323 -7.59393e-13 -3.05972 -0.0937068 0.0612327 -1.28786e-14 -3.33067e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 323 324 2.65087 0.0899758 -0.0704017 0.00424512 0.052903 0.114039 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 274 324 -7.60281e-13 -3.05972 -0.0937068 0.0612327 -1.33227e-14 -3.33067e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 324 325 2.65782 0.0902859 -0.0707719 0.00425136 0.0530423 0.113974 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 275 325 -7.63405e-13 -3.05972 -0.0937068 0.0612327 -1.33227e-14 -3.33067e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 325 326 2.66477 0.090595 -0.0711428 0.00425758 0.0531815 0.113909 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 276 326 -7.64722e-13 -3.05972 -0.0937068 0.0612327 -1.33227e-14 -3.33067e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 326 327 2.67172 0.0909032 -0.0715145 0.00426379 0.0533207 0.113844 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 277 327 -7.67386e-13 -3.05972 -0.0937068 0.0612327 -1.33227e-14 -3.33067e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 327 328 2.67866 0.0912105 -0.0718869 0.00426997 0.0534598 0.113779 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 278 328 -7.68274e-13 -3.05972 -0.0937068 0.0612327 -1.33227e-14 -3.33067e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 328 329 2.68559 0.0915169 -0.07226 0.00427614 0.0535988 0.113714 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 279 329 -7.70051e-13 -3.05972 -0.0937068 0.0612327 -1.33227e-14 -3.33067e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 329 330 2.69252 0.0918224 -0.0726339 0.00428229 0.0537377 0.113649 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 280 330 -7.72715e-13 -3.05972 -0.0937068 0.0612327 -1.33227e-14 -3.33067e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 330 331 2.69945 0.092127 -0.0730086 0.00428843 0.0538765 0.113583 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 281 331 -7.74492e-13 -3.05972 -0.0937068 0.0612327 -1.33227e-14 -3.33067e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 331 332 2.70638 0.0924306 -0.073384 0.00429454 0.0540153 0.113518 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 282 332 -7.79821e-13 -3.05972 -0.0937068 0.0612327 -1.33227e-14 -3.33067e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 332 333 2.7133 0.0927334 -0.0737602 0.00430064 0.054154 0.113452 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 283 333 -7.76268e-13 -3.05972 -0.0937068 0.0612327 -1.33227e-14 -3.28626e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 333 334 2.72021 0.0930352 -0.0741371 0.00430671 0.0542926 0.113386 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 284 334 -7.80709e-13 -3.05972 -0.0937068 0.0612327 -1.33227e-14 -3.28626e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 334 335 2.72712 0.0933361 -0.0745147 0.00431277 0.0544311 0.11332 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 285 335 -7.8515e-13 -3.05972 -0.0937068 0.0612327 -1.37668e-14 -3.28626e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 335 336 2.73403 0.093636 -0.074893 0.00431881 0.0545696 0.113253 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 286 336 -7.8515e-13 -3.05972 -0.0937068 0.0612327 -1.37668e-14 -3.28626e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 336 337 2.74093 0.0939351 -0.0752721 0.00432484 0.0547079 0.113187 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 287 337 -7.86926e-13 -3.05972 -0.0937068 0.0612327 -1.37668e-14 -3.28626e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 337 338 2.74783 0.0942332 -0.075652 0.00433084 0.0548462 0.11312 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 288 338 -7.88924e-13 -3.05972 -0.0937068 0.0612327 -1.37668e-14 -3.28626e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 338 339 2.75473 0.0945303 -0.0760325 0.00433682 0.0549844 0.113053 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 289 339 -7.90479e-13 -3.05972 -0.0937068 0.0612327 -1.37668e-14 -3.28626e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 339 340 2.76162 0.0948266 -0.0764138 0.00434279 0.0551225 0.112986 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 290 340 -7.93143e-13 -3.05972 -0.0937068 0.0612327 -1.37668e-14 -3.28626e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 340 341 2.76851 0.0951219 -0.0767958 0.00434874 0.0552605 0.112919 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 291 341 -7.9492e-13 -3.05972 -0.0937068 0.0612327 -1.37668e-14 -3.28626e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 341 342 2.77539 0.0954162 -0.0771785 0.00435467 0.0553985 0.112851 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 292 342 -7.97584e-13 -3.05972 -0.0937068 0.0612327 -1.37668e-14 -3.28626e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 342 343 2.78227 0.0957096 -0.077562 0.00436058 0.0555364 0.112784 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 293 343 -7.99361e-13 -3.05972 -0.0937068 0.0612327 -1.37668e-14 -3.28626e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 343 344 2.78914 0.0960021 -0.0779462 0.00436647 0.0556741 0.112716 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 294 344 -7.99361e-13 -3.05972 -0.0937068 0.0612327 -1.37668e-14 -3.28626e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 344 345 2.79601 0.0962937 -0.078331 0.00437235 0.0558118 0.112648 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 295 345 -8.01137e-13 -3.05972 -0.0937068 0.0612327 -1.42109e-14 -3.28626e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 345 346 2.80288 0.0965843 -0.0787166 0.0043782 0.0559495 0.11258 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 296 346 -8.02913e-13 -3.05972 -0.0937068 0.0612327 -1.42109e-14 -3.28626e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 346 347 2.80974 0.0968739 -0.0791029 0.00438404 0.056087 0.112512 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 297 347 -8.05578e-13 -3.05972 -0.0937068 0.0612327 -1.42109e-14 -3.28626e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 347 348 2.8166 0.0971626 -0.07949 0.00438985 0.0562245 0.112443 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 298 348 -8.08242e-13 -3.05972 -0.0937068 0.0612327 -1.42109e-14 -3.28626e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 348 349 2.82345 0.0974504 -0.0798777 0.00439565 0.0563618 0.112375 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 299 349 -8.10907e-13 -3.05972 -0.0937068 0.0612327 -1.42109e-14 -3.28626e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 349 350 2.8303 0.0977372 -0.0802661 0.00440143 0.0564991 0.112306 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 300 350 -8.12567e-13 -3.05972 -0.0937068 0.0612327 -1.42109e-14 -3.28626e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 350 351 2.83715 0.0980231 -0.0806552 0.00440719 0.0566363 0.112237 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 301 351 -8.1446e-13 -3.05972 -0.0937068 0.0612327 -1.42109e-14 -3.28626e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 351 352 2.84399 0.098308 -0.0810451 0.00441293 0.0567735 0.112168 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 302 352 -8.17124e-13 -3.05972 -0.0937068 0.0612327 -1.42109e-14 -3.28626e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 352 353 2.85083 0.0985919 -0.0814356 0.00441866 0.0569105 0.112099 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 303 353 -8.16236e-13 -3.05972 -0.0937068 0.0612327 -1.42109e-14 -3.28626e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 353 354 2.85766 0.0988749 -0.0818268 0.00442436 0.0570474 0.112029 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 304 354 -8.22453e-13 -3.05972 -0.0937068 0.0612327 -1.42109e-14 -3.28626e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 354 355 2.86449 0.0991569 -0.0822187 0.00443005 0.0571843 0.11196 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 305 355 -8.2423e-13 -3.05972 -0.0937068 0.0612327 -1.42109e-14 -3.28626e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 355 356 2.87131 0.099438 -0.0826113 0.00443571 0.0573211 0.11189 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 306 356 -8.2423e-13 -3.05972 -0.0937068 0.0612327 -1.42109e-14 -3.28626e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 356 357 2.87813 0.0997181 -0.0830046 0.00444136 0.0574578 0.11182 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 307 357 -8.2423e-13 -3.05972 -0.0937068 0.0612327 -1.42109e-14 -3.28626e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 357 358 2.88494 0.0999973 -0.0833985 0.00444698 0.0575944 0.11175 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 308 358 -8.31335e-13 -3.05972 -0.0937068 0.0612327 -1.46549e-14 -3.28626e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 358 359 2.89175 0.100275 -0.0837932 0.00445259 0.0577309 0.11168 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 309 359 -8.30447e-13 -3.05972 -0.0937068 0.0612327 -1.46549e-14 -3.28626e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 359 360 2.89856 0.100553 -0.0841885 0.00445818 0.0578674 0.111609 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 310 360 -8.32223e-13 -3.05972 -0.0937068 0.0612327 -1.46549e-14 -3.28626e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 360 361 2.90536 0.100829 -0.0845845 0.00446375 0.0580037 0.111539 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 311 361 -8.34444e-13 -3.05972 -0.0937068 0.0612327 -1.46549e-14 -3.28626e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 361 362 2.91216 0.101104 -0.0849812 0.0044693 0.05814 0.111468 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 312 362 -8.35998e-13 -3.05972 -0.0937068 0.0612327 -1.46549e-14 -3.24185e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 362 363 2.91895 0.101378 -0.0853786 0.00447483 0.0582762 0.111397 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 313 363 -8.38218e-13 -3.05972 -0.0937068 0.0612327 -1.46549e-14 -3.24185e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 363 364 2.92574 0.101652 -0.0857766 0.00448034 0.0584123 0.111326 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 314 364 -8.38885e-13 -3.05972 -0.0937068 0.0612327 -1.46549e-14 -3.24185e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 364 365 2.93253 0.101924 -0.0861753 0.00448583 0.0585483 0.111255 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 315 365 -8.42881e-13 -3.05972 -0.0937068 0.0612327 -1.46549e-14 -3.24185e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 365 366 2.93931 0.102196 -0.0865747 0.00449131 0.0586842 0.111183 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 316 366 -8.41105e-13 -3.05972 -0.0937068 0.0612327 -1.46549e-14 -3.24185e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 366 367 2.94608 0.102466 -0.0869747 0.00449676 0.0588201 0.111112 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 317 367 -8.43769e-13 -3.05972 -0.0937068 0.0612327 -1.46549e-14 -3.24185e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 367 368 2.95285 0.102735 -0.0873754 0.00450219 0.0589558 0.11104 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 318 368 -8.45546e-13 -3.05972 -0.0937068 0.0612327 -1.5099e-14 -3.24185e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 368 369 2.95962 0.103004 -0.0877767 0.00450761 0.0590915 0.110968 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 319 369 -8.50875e-13 -3.05972 -0.0937068 0.0612327 -1.5099e-14 -3.24185e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 369 370 2.96638 0.103271 -0.0881787 0.004513 0.059227 0.110896 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 320 370 -8.54428e-13 -3.05972 -0.0937068 0.0612327 -1.5099e-14 -3.24185e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 370 371 2.97314 0.103538 -0.0885814 0.00451838 0.0593625 0.110824 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 321 371 -8.52651e-13 -3.05972 -0.0937068 0.0612327 -1.5099e-14 -3.24185e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 371 372 2.9799 0.103803 -0.0889847 0.00452373 0.0594979 0.110751 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 322 372 -8.55316e-13 -3.05972 -0.0937068 0.0612327 -1.5099e-14 -3.24185e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 372 373 2.98664 0.104068 -0.0893886 0.00452907 0.0596332 0.110679 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 323 373 -8.57092e-13 -3.05972 -0.0937068 0.0612327 -1.5099e-14 -3.24185e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 373 374 2.99339 0.104331 -0.0897932 0.00453438 0.0597685 0.110606 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 324 374 -8.59313e-13 -3.05972 -0.0937068 0.0612327 -1.5099e-14 -3.24185e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 374 375 3.00013 0.104594 -0.0901985 0.00453968 0.0599036 0.110533 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 325 375 -8.60968e-13 -3.05972 -0.0937068 0.0612327 -1.5099e-14 -3.24185e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 375 376 3.00686 0.104855 -0.0906044 0.00454496 0.0600386 0.11046 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 326 376 -8.63309e-13 -3.05972 -0.0937068 0.0612327 -1.5099e-14 -3.24185e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 376 377 3.0136 0.105116 -0.0910109 0.00455021 0.0601736 0.110387 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 327 377 -8.64198e-13 -3.05972 -0.0937068 0.0612327 -1.5099e-14 -3.24185e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 377 378 3.02032 0.105375 -0.0914181 0.00455545 0.0603085 0.110313 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 328 378 -8.6775e-13 -3.05972 -0.0937068 0.0612327 -1.5099e-14 -3.24185e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 378 379 3.02704 0.105634 -0.0918259 0.00456067 0.0604432 0.11024 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 329 379 -8.68638e-13 -3.05972 -0.0937068 0.0612327 -1.55431e-14 -3.24185e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 379 380 3.03376 0.105891 -0.0922343 0.00456587 0.0605779 0.110166 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 330 380 -8.72191e-13 -3.05972 -0.0937068 0.0612327 -1.55431e-14 -3.24185e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 380 381 3.04047 0.106148 -0.0926434 0.00457104 0.0607125 0.110092 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 331 381 -8.73968e-13 -3.05972 -0.0937068 0.0612327 -1.55431e-14 -3.24185e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 381 382 3.04718 0.106403 -0.0930531 0.0045762 0.060847 0.110018 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 332 382 -8.73968e-13 -3.05972 -0.0937068 0.0612327 -1.55431e-14 -3.19744e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 382 383 3.05389 0.106658 -0.0934634 0.00458134 0.0609815 0.109944 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 333 383 -8.75744e-13 -3.05972 -0.0937068 0.0612327 -1.55431e-14 -3.24185e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 383 384 3.06059 0.106911 -0.0938743 0.00458645 0.0611158 0.109869 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 334 384 -8.7752e-13 -3.05972 -0.0937068 0.0612327 -1.55431e-14 -3.24185e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 384 385 3.06728 0.107164 -0.0942859 0.00459155 0.06125 0.109795 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 335 385 -8.78408e-13 -3.05972 -0.0937068 0.0612327 -1.55431e-14 -3.19744e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 385 386 3.07397 0.107415 -0.094698 0.00459663 0.0613842 0.10972 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 336 386 -8.82849e-13 -3.05972 -0.0937068 0.0612327 -1.55431e-14 -3.19744e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 386 387 3.08066 0.107666 -0.0951108 0.00460169 0.0615182 0.109645 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 337 387 -8.8396e-13 -3.05972 -0.0937068 0.0612327 -1.55431e-14 -3.19744e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 387 388 3.08734 0.107915 -0.0955242 0.00460672 0.0616522 0.10957 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 338 388 -8.8618e-13 -3.05972 -0.0937068 0.0612327 -1.55431e-14 -3.19744e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 388 389 3.09401 0.108164 -0.0959382 0.00461174 0.061786 0.109495 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 339 389 -8.88178e-13 -3.05972 -0.0937068 0.0612327 -1.55431e-14 -3.19744e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 389 390 3.10068 0.108411 -0.0963528 0.00461674 0.0619198 0.109419 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 340 390 -8.89955e-13 -3.05972 -0.0937068 0.0612327 -1.55431e-14 -3.19744e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 390 391 3.10735 0.108657 -0.0967681 0.00462171 0.0620535 0.109344 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 341 391 -8.91731e-13 -3.05972 -0.0937068 0.0612327 -1.59872e-14 -3.19744e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 391 392 3.11401 0.108903 -0.0971839 0.00462667 0.0621871 0.109268 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 342 392 -8.91731e-13 -3.05972 -0.0937068 0.0612327 -1.59872e-14 -3.19744e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 392 393 3.12067 0.109147 -0.0976003 0.0046316 0.0623206 0.109192 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 343 393 -8.93507e-13 -3.05972 -0.0937068 0.0612327 -1.59872e-14 -3.19744e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 393 394 3.12732 0.109391 -0.0980173 0.00463652 0.062454 0.109116 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 344 394 -8.98837e-13 -3.05972 -0.0937068 0.0612327 -1.59872e-14 -3.19744e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 394 395 3.13397 0.109633 -0.0984349 0.00464141 0.0625873 0.10904 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 345 395 -9.00613e-13 -3.05972 -0.0937068 0.0612327 -1.59872e-14 -3.19744e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 395 396 3.14062 0.109874 -0.0988531 0.00464629 0.0627206 0.108964 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 346 396 -9.00613e-13 -3.05972 -0.0937068 0.0612327 -1.59872e-14 -3.19744e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 396 397 3.14726 0.110115 -0.0992719 0.00465114 0.0628537 0.108887 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 347 397 -9.01501e-13 -3.05972 -0.0937068 0.0612327 -1.59872e-14 -3.19744e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 397 398 3.15389 0.110354 -0.0996913 0.00465598 0.0629867 0.10881 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 348 398 -9.04166e-13 -3.05972 -0.0937068 0.0612327 -1.59872e-14 -3.19744e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 398 399 3.16052 0.110592 -0.100111 0.00466079 0.0631197 0.108734 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 349 399 -9.05498e-13 -3.05972 -0.0937068 0.0612327 -1.59872e-14 -3.19744e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 399 400 3.16714 0.110829 -0.100532 0.00466558 0.0632525 0.108657 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 350 400 -9.08561e-13 -3.05972 -0.0937068 0.0612327 -1.59872e-14 -3.19744e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 400 401 3.17376 0.111065 -0.100953 0.00467036 0.0633853 0.108579 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 351 401 -9.09495e-13 -3.05972 -0.0937068 0.0612327 -1.59872e-14 -3.19744e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 401 402 3.18038 0.111301 -0.101375 0.00467511 0.063518 0.108502 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 352 402 -9.11271e-13 -3.05972 -0.0937068 0.0612327 -1.64313e-14 -3.19744e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 402 403 3.18699 0.111535 -0.101797 0.00467984 0.0636505 0.108424 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 353 403 -9.14824e-13 -3.05972 -0.0937068 0.0612327 -1.64313e-14 -3.19744e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 403 404 3.19359 0.111768 -0.10222 0.00468455 0.063783 0.108347 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 354 404 -9.14824e-13 -3.05972 -0.0937068 0.0612327 -1.64313e-14 -3.19744e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 404 405 3.20019 0.112 -0.102643 0.00468924 0.0639154 0.108269 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 355 405 -9.18376e-13 -3.05972 -0.0937068 0.0612327 -1.64313e-14 -3.19744e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 405 406 3.20679 0.112231 -0.103067 0.00469391 0.0640477 0.108191 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 356 406 -9.166e-13 -3.05972 -0.0937068 0.0612327 -1.64313e-14 -3.19744e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 406 407 3.21338 0.112461 -0.103492 0.00469856 0.0641799 0.108113 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 357 407 -9.21929e-13 -3.05972 -0.0937068 0.0612327 -1.64313e-14 -3.19744e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 407 408 3.21997 0.11269 -0.103917 0.00470319 0.064312 0.108034 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 358 408 -9.23706e-13 -3.05972 -0.0937068 0.0612327 -1.64313e-14 -3.19744e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 408 409 3.22655 0.112918 -0.104343 0.00470779 0.064444 0.107956 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 359 409 -9.25482e-13 -3.05972 -0.0937068 0.0612327 -1.64313e-14 -3.15303e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 409 410 3.23313 0.113145 -0.104769 0.00471238 0.0645759 0.107877 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 360 410 -9.28146e-13 -3.05972 -0.0937068 0.0612327 -1.64313e-14 -3.19744e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 410 411 3.2397 0.11337 -0.105196 0.00471695 0.0647077 0.107799 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 361 411 -9.29923e-13 -3.05972 -0.0937068 0.0612327 -1.64313e-14 -3.15303e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 411 412 3.24626 0.113595 -0.105623 0.00472149 0.0648394 0.10772 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 362 412 -9.31255e-13 -3.05972 -0.0937068 0.0612327 -1.64313e-14 -3.15303e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 412 413 3.25283 0.113819 -0.106051 0.00472601 0.064971 0.10764 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 363 413 -9.32809e-13 -3.05972 -0.0937068 0.0612327 -1.68754e-14 -3.15303e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 413 414 3.25938 0.114041 -0.106479 0.00473052 0.0651025 0.107561 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 364 414 -9.3614e-13 -3.05972 -0.0937068 0.0612327 -1.68754e-14 -3.15303e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 414 415 3.26594 0.114263 -0.106908 0.004735 0.0652339 0.107482 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 365 415 -9.35252e-13 -3.05972 -0.0937068 0.0612327 -1.68754e-14 -3.15303e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 415 416 3.27248 0.114484 -0.107338 0.00473946 0.0653653 0.107402 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 366 416 -9.37916e-13 -3.05972 -0.0937068 0.0612327 -1.68754e-14 -3.15303e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 416 417 3.27903 0.114703 -0.107768 0.0047439 0.0654965 0.107322 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 367 417 -9.41469e-13 -3.05972 -0.0937068 0.0612327 -1.68754e-14 -3.15303e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 417 418 3.28556 0.114922 -0.108198 0.00474832 0.0656276 0.107242 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 368 418 -9.43245e-13 -3.05972 -0.0937068 0.0612327 -1.68754e-14 -3.15303e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 418 419 3.2921 0.115139 -0.10863 0.00475272 0.0657587 0.107162 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 369 419 -9.45022e-13 -3.05972 -0.0937068 0.0612327 -1.68754e-14 -3.15303e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 419 420 3.29862 0.115355 -0.109061 0.0047571 0.0658896 0.107082 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 370 420 -9.43245e-13 -3.05972 -0.0937068 0.0612327 -1.68754e-14 -3.15303e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 420 421 3.30515 0.115571 -0.109493 0.00476145 0.0660204 0.107002 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 371 421 -9.48575e-13 -3.05972 -0.0937068 0.0612327 -1.68754e-14 -3.15303e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 421 422 3.31166 0.115785 -0.109926 0.00476579 0.0661512 0.106921 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 372 422 -9.50351e-13 -3.05972 -0.0937068 0.0612327 -1.68754e-14 -3.15303e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 422 423 3.31818 0.115998 -0.110359 0.0047701 0.0662818 0.10684 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 373 423 -9.52127e-13 -3.05972 -0.0937068 0.0612327 -1.68754e-14 -3.15303e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 423 424 3.32469 0.11621 -0.110793 0.00477439 0.0664124 0.106759 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 374 424 -9.53904e-13 -3.05972 -0.0937068 0.0612327 -1.68754e-14 -3.15303e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 424 425 3.33119 0.116421 -0.111227 0.00477867 0.0665428 0.106678 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 375 425 -9.55304e-13 -3.05972 -0.0937068 0.0612327 -1.73195e-14 -3.15303e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 425 426 3.33769 0.116631 -0.111662 0.00478292 0.0666732 0.106597 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 376 426 -9.57456e-13 -3.05972 -0.0937068 0.0612327 -1.73195e-14 -3.15303e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 426 427 3.34418 0.11684 -0.112098 0.00478714 0.0668034 0.106516 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 377 427 -9.58345e-13 -3.05972 -0.0937068 0.0612327 -1.73195e-14 -3.15303e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 427 428 3.35067 0.117048 -0.112533 0.00479135 0.0669336 0.106434 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 378 428 -9.61009e-13 -3.05972 -0.0937068 0.0612327 -1.73195e-14 -3.10862e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 428 429 3.35715 0.117254 -0.11297 0.00479554 0.0670636 0.106352 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 379 429 -9.64562e-13 -3.05972 -0.0937068 0.0612327 -1.73195e-14 -3.10862e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 429 430 3.36363 0.11746 -0.113407 0.0047997 0.0671936 0.10627 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 380 430 -9.68114e-13 -3.05972 -0.0937068 0.0612327 -1.73195e-14 -3.10862e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 430 431 3.3701 0.117665 -0.113844 0.00480385 0.0673234 0.106188 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 381 431 -9.68114e-13 -3.05972 -0.0937068 0.0612327 -1.73195e-14 -3.15303e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 431 432 3.37657 0.117868 -0.114282 0.00480797 0.0674532 0.106106 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 382 432 -9.66338e-13 -3.05972 -0.0937068 0.0612327 -1.73195e-14 -3.10862e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 432 433 3.38303 0.118071 -0.11472 0.00481207 0.0675828 0.106024 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 383 433 -9.69891e-13 -3.05972 -0.0937068 0.0612327 -1.73195e-14 -3.10862e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 433 434 3.38949 0.118272 -0.115159 0.00481615 0.0677124 0.105941 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 384 434 -9.71667e-13 -3.05972 -0.0937068 0.0612327 -1.73195e-14 -3.10862e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 434 435 3.39594 0.118473 -0.115598 0.00482021 0.0678418 0.105859 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 385 435 -9.74332e-13 -3.05972 -0.0937068 0.0612327 -1.73195e-14 -3.10862e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 435 436 3.40239 0.118672 -0.116038 0.00482425 0.0679711 0.105776 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 386 436 -9.76108e-13 -3.05972 -0.0937068 0.0612327 -1.77636e-14 -3.10862e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 436 437 3.40883 0.11887 -0.116478 0.00482826 0.0681004 0.105693 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 387 437 -9.7744e-13 -3.05972 -0.0937068 0.0612327 -1.77636e-14 -3.10862e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 437 438 3.41527 0.119067 -0.116919 0.00483226 0.0682295 0.10561 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 388 438 -9.79439e-13 -3.05972 -0.0937068 0.0612327 -1.77636e-14 -3.10862e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 438 439 3.4217 0.119263 -0.11736 0.00483623 0.0683586 0.105526 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 389 439 -9.81437e-13 -3.05972 -0.0937068 0.0612327 -1.77636e-14 -3.10862e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 439 440 3.42813 0.119458 -0.117802 0.00484018 0.0684875 0.105443 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 390 440 -9.83214e-13 -3.05972 -0.0937068 0.0612327 -1.77636e-14 -3.10862e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 440 441 3.43455 0.119652 -0.118244 0.00484411 0.0686164 0.105359 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 391 441 -9.85878e-13 -3.05972 -0.0937068 0.0612327 -1.77636e-14 -3.10862e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 441 442 3.44097 0.119845 -0.118687 0.00484801 0.0687451 0.105276 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 392 442 -9.89431e-13 -3.05972 -0.0937068 0.0612327 -1.77636e-14 -3.10862e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 442 443 3.44738 0.120036 -0.11913 0.0048519 0.0688737 0.105192 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 393 443 -9.87654e-13 -3.05972 -0.0937068 0.0612327 -1.77636e-14 -3.10862e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 443 444 3.45378 0.120227 -0.119574 0.00485576 0.0690023 0.105108 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 394 444 -9.89431e-13 -3.05972 -0.0937068 0.0612327 -1.77636e-14 -3.10862e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 444 445 3.46018 0.120416 -0.120018 0.00485961 0.0691307 0.105023 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 395 445 -9.92983e-13 -3.05972 -0.0937068 0.0612327 -1.77636e-14 -3.10862e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 445 446 3.46658 0.120605 -0.120462 0.00486343 0.069259 0.104939 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 396 446 -9.9476e-13 -3.05972 -0.0937068 0.0612327 -1.77636e-14 -3.10862e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 446 447 3.47297 0.120792 -0.120907 0.00486723 0.0693873 0.104854 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 397 447 -9.92983e-13 -3.05972 -0.0937068 0.0612327 -1.77636e-14 -3.10862e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 447 448 3.47936 0.120978 -0.121353 0.004871 0.0695154 0.10477 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 398 448 -9.97424e-13 -3.05972 -0.0937068 0.0612327 -1.82077e-14 -3.10862e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 448 449 3.48574 0.121164 -0.121799 0.00487476 0.0696434 0.104685 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 399 449 -1.00009e-12 -3.05972 -0.0937068 0.0612327 -1.82077e-14 -3.10862e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 449 450 3.49211 0.121348 -0.122245 0.00487849 0.0697713 0.1046 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 400 450 -1.00115e-12 -3.05972 -0.0937068 0.0612327 -1.82077e-14 -3.10862e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 450 451 3.49848 0.121531 -0.122692 0.00488221 0.0698991 0.104515 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 401 451 -1.0032e-12 -3.05972 -0.0937068 0.0612327 -1.82077e-14 -3.06422e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 451 452 3.50485 0.121713 -0.123139 0.0048859 0.0700269 0.104429 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 402 452 -1.00453e-12 -3.05972 -0.0937068 0.0612327 -1.82077e-14 -3.06422e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 452 453 3.51121 0.121893 -0.123587 0.00488956 0.0701545 0.104344 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 403 453 -1.00719e-12 -3.05972 -0.0937068 0.0612327 -1.82077e-14 -3.10862e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 453 454 3.51756 0.122073 -0.124035 0.00489321 0.070282 0.104258 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 404 454 -1.00897e-12 -3.05972 -0.0937068 0.0612327 -1.82077e-14 -3.06422e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 454 455 3.52391 0.122252 -0.124484 0.00489683 0.0704094 0.104172 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 405 455 -1.00897e-12 -3.05972 -0.0937068 0.0612327 -1.82077e-14 -3.06422e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 455 456 3.53025 0.122429 -0.124933 0.00490044 0.0705366 0.104086 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 406 456 -1.0143e-12 -3.05972 -0.0937068 0.0612327 -1.82077e-14 -3.06422e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 456 457 3.53659 0.122605 -0.125382 0.00490402 0.0706638 0.104 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 407 457 -1.0143e-12 -3.05972 -0.0937068 0.0612327 -1.82077e-14 -3.06422e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 457 458 3.54292 0.122781 -0.125832 0.00490758 0.0707909 0.103914 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 408 458 -1.0143e-12 -3.05972 -0.0937068 0.0612327 -1.82077e-14 -3.06422e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 458 459 3.54925 0.122955 -0.126282 0.00491111 0.0709179 0.103827 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 409 459 -1.01785e-12 -3.05972 -0.0937068 0.0612327 -1.82077e-14 -3.06422e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 459 460 3.55557 0.123128 -0.126733 0.00491463 0.0710448 0.103741 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 410 460 -1.01785e-12 -3.05972 -0.0937068 0.0612327 -1.86517e-14 -3.06422e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 460 461 3.56189 0.1233 -0.127184 0.00491812 0.0711715 0.103654 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 411 461 -1.02141e-12 -3.05972 -0.0937068 0.0612327 -1.86517e-14 -3.06422e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 461 462 3.5682 0.123471 -0.127636 0.00492159 0.0712982 0.103567 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 412 462 -1.02274e-12 -3.05972 -0.0937068 0.0612327 -1.86517e-14 -3.06422e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 462 463 3.57451 0.123641 -0.128088 0.00492504 0.0714247 0.10348 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 413 463 -1.02474e-12 -3.05972 -0.0937068 0.0612327 -1.86517e-14 -3.06422e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 463 464 3.58081 0.123809 -0.12854 0.00492847 0.0715512 0.103393 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 414 464 -1.02585e-12 -3.05972 -0.0937068 0.0612327 -1.86517e-14 -3.06422e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 464 465 3.5871 0.123977 -0.128993 0.00493187 0.0716775 0.103305 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 415 465 -1.02673e-12 -3.05972 -0.0937068 0.0612327 -1.86517e-14 -3.06422e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 465 466 3.59339 0.124143 -0.129447 0.00493525 0.0718038 0.103218 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 416 466 -1.02851e-12 -3.05972 -0.0937068 0.0612327 -1.86517e-14 -3.06422e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 466 467 3.59968 0.124308 -0.1299 0.00493861 0.0719299 0.10313 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 417 467 -1.02851e-12 -3.05972 -0.0937068 0.0612327 -1.86517e-14 -3.06422e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 467 468 3.60596 0.124473 -0.130354 0.00494195 0.0720559 0.103042 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 418 468 -1.03562e-12 -3.05972 -0.0937068 0.0612327 -1.86517e-14 -3.06422e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 468 469 3.61223 0.124636 -0.130809 0.00494526 0.0721818 0.102954 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 419 469 -1.03206e-12 -3.05972 -0.0937068 0.0612327 -1.86517e-14 -3.06422e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 469 470 3.6185 0.124798 -0.131264 0.00494856 0.0723076 0.102866 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 420 470 -1.04095e-12 -3.05972 -0.0937068 0.0612327 -1.86517e-14 -3.01981e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 470 471 3.62476 0.124959 -0.131719 0.00495183 0.0724333 0.102778 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 421 471 -1.03917e-12 -3.05972 -0.0937068 0.0612327 -1.86517e-14 -3.01981e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 471 472 3.63102 0.125118 -0.132174 0.00495508 0.0725589 0.102689 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 422 472 -1.04095e-12 -3.05972 -0.0937068 0.0612327 -1.90958e-14 -3.01981e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 472 473 3.63727 0.125277 -0.13263 0.0049583 0.0726844 0.102601 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 423 473 -1.04272e-12 -3.05972 -0.0937068 0.0612327 -1.90958e-14 -3.01981e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 473 474 3.64352 0.125435 -0.133087 0.00496151 0.0728098 0.102512 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 424 474 -1.04317e-12 -3.05972 -0.0937068 0.0612327 -1.90958e-14 -3.01981e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 474 475 3.64976 0.125591 -0.133544 0.00496469 0.0729351 0.102423 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 425 475 -1.04606e-12 -3.05972 -0.0937068 0.0612327 -1.90958e-14 -3.01981e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 475 476 3.656 0.125746 -0.134001 0.00496785 0.0730602 0.102334 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 426 476 -1.04716e-12 -3.05972 -0.0937068 0.0612327 -1.90958e-14 -3.01981e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 476 477 3.66223 0.1259 -0.134458 0.00497099 0.0731853 0.102245 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 427 477 -1.04983e-12 -3.05972 -0.0937068 0.0612327 -1.90958e-14 -3.01981e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 477 478 3.66845 0.126053 -0.134916 0.0049741 0.0733102 0.102155 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 428 478 -1.0516e-12 -3.05972 -0.0937068 0.0612327 -1.90958e-14 -3.01981e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 478 479 3.67467 0.126205 -0.135375 0.00497719 0.073435 0.102066 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 429 479 -1.0516e-12 -3.05972 -0.0937068 0.0612327 -1.90958e-14 -3.01981e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 479 480 3.68089 0.126356 -0.135833 0.00498026 0.0735598 0.101976 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 430 480 -1.04983e-12 -3.05972 -0.0937068 0.0612327 -1.90958e-14 -3.01981e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 480 481 3.68709 0.126506 -0.136292 0.00498331 0.0736844 0.101886 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 431 481 -1.05693e-12 -3.05972 -0.0937068 0.0612327 -1.90958e-14 -3.01981e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 481 482 3.6933 0.126654 -0.136752 0.00498633 0.0738089 0.101796 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 432 482 -1.06049e-12 -3.05972 -0.0937068 0.0612327 -1.95399e-14 -3.01981e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 482 483 3.69949 0.126802 -0.137212 0.00498934 0.0739333 0.101706 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 433 483 -1.05871e-12 -3.05972 -0.0937068 0.0612327 -1.95399e-14 -3.01981e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 483 484 3.70569 0.126948 -0.137672 0.00499232 0.0740576 0.101616 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 434 484 -1.06049e-12 -3.05972 -0.0937068 0.0612327 -1.95399e-14 -3.01981e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 484 485 3.71187 0.127093 -0.138132 0.00499527 0.0741817 0.101525 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 435 485 -1.06404e-12 -3.05972 -0.0937068 0.0612327 -1.95399e-14 -3.01981e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 485 486 3.71805 0.127237 -0.138593 0.00499821 0.0743058 0.101435 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 436 486 -1.06493e-12 -3.05972 -0.0937068 0.0612327 -1.95399e-14 -3.01981e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 486 487 3.72423 0.12738 -0.139054 0.00500112 0.0744298 0.101344 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 437 487 -1.06737e-12 -3.05972 -0.0937068 0.0612327 -1.95399e-14 -3.01981e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 487 488 3.7304 0.127522 -0.139516 0.00500401 0.0745536 0.101253 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 438 488 -1.0687e-12 -3.05972 -0.0937068 0.0612327 -1.95399e-14 -3.01981e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 488 489 3.73656 0.127663 -0.139978 0.00500688 0.0746773 0.101162 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 439 489 -1.07114e-12 -3.05972 -0.0937068 0.0612327 -1.95399e-14 -2.9754e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 489 490 3.74272 0.127802 -0.14044 0.00500972 0.074801 0.101071 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 440 490 -1.0747e-12 -3.05972 -0.0937068 0.0612327 -1.95399e-14 -2.9754e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 490 491 3.74887 0.12794 -0.140903 0.00501254 0.0749245 0.100979 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 441 491 -1.0747e-12 -3.05972 -0.0937068 0.0612327 -1.95399e-14 -2.9754e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 491 492 3.75502 0.128078 -0.141366 0.00501534 0.0750479 0.100888 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 442 492 -1.0747e-12 -3.05972 -0.0937068 0.0612327 -1.95399e-14 -2.9754e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 492 493 3.76116 0.128214 -0.141829 0.00501812 0.0751712 0.100796 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 443 493 -1.07825e-12 -3.05972 -0.0937068 0.0612327 -1.95399e-14 -2.9754e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 493 494 3.7673 0.128349 -0.142292 0.00502087 0.0752943 0.100704 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 444 494 -1.07825e-12 -3.05972 -0.0937068 0.0612327 -1.95399e-14 -2.9754e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 494 495 3.77343 0.128483 -0.142756 0.00502361 0.0754174 0.100612 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 445 495 -1.08002e-12 -3.05972 -0.0937068 0.0612327 -1.95399e-14 -2.9754e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 495 496 3.77955 0.128615 -0.143221 0.00502631 0.0755403 0.10052 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 446 496 -1.08358e-12 -3.05972 -0.0937068 0.0612327 -1.9984e-14 -2.9754e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 496 497 3.78567 0.128747 -0.143685 0.005029 0.0756632 0.100428 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 447 497 -1.08535e-12 -3.05972 -0.0937068 0.0612327 -1.9984e-14 -2.9754e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 497 498 3.79178 0.128877 -0.14415 0.00503166 0.0757859 0.100335 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 448 498 -1.08713e-12 -3.05972 -0.0937068 0.0612327 -2.39808e-14 -3.55271e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 498 499 3.79789 0.129007 -0.144615 0.0050343 0.0759085 0.100243 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 449 499 -1.08846e-12 -3.05972 -0.0937068 0.0612327 -1.9984e-14 -2.9754e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 499 500 3.80399 0.129135 -0.145081 0.00503692 0.076031 0.10015 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 450 500 -1.08999e-12 -3.05972 -0.0937068 0.0612327 -2.39808e-14 -3.55271e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 500 501 3.81009 0.129262 -0.145547 0.00503951 0.0761534 0.100057 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 451 501 -1.09157e-12 -3.05972 -0.0937068 0.0612327 -1.9984e-14 -2.9754e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 501 502 3.81618 0.129388 -0.146013 0.00504209 0.0762757 0.0999639 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 452 502 -1.09424e-12 -3.05972 -0.0937068 0.0612327 -2.39808e-14 -3.55271e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 502 503 3.82226 0.129512 -0.146479 0.00504464 0.0763978 0.0998707 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 453 503 -1.09424e-12 -3.05972 -0.0937068 0.0612327 -1.9984e-14 -2.9754e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 503 504 3.82834 0.129636 -0.146946 0.00504716 0.0765199 0.0997774 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 454 504 -1.09779e-12 -3.05972 -0.0937068 0.0612327 -2.39808e-14 -3.55271e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 504 505 3.83441 0.129758 -0.147413 0.00504967 0.0766418 0.0996839 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 455 505 -1.09956e-12 -3.05972 -0.0937068 0.0612327 -1.9984e-14 -2.9754e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 505 506 3.84048 0.12988 -0.14788 0.00505215 0.0767636 0.0995902 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 456 506 -1.09601e-12 -3.05972 -0.0937068 0.0612327 -2.44249e-14 -3.55271e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 506 507 3.84654 0.13 -0.148348 0.0050546 0.0768853 0.0994964 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 457 507 -1.10134e-12 -3.05972 -0.0937068 0.0612327 -2.04281e-14 -2.9754e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 507 508 3.8526 0.130119 -0.148816 0.00505704 0.0770069 0.0994025 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 458 508 -1.10489e-12 -3.05972 -0.0937068 0.0612327 -2.44249e-14 -3.55271e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 508 509 3.85865 0.130237 -0.149284 0.00505945 0.0771284 0.0993084 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 459 509 -1.10489e-12 -3.05972 -0.0937068 0.0612327 -2.04281e-14 -2.93099e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 509 510 3.86469 0.130354 -0.149753 0.00506184 0.0772498 0.0992141 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 460 510 -1.10667e-12 -3.05972 -0.0937068 0.0612327 -2.44249e-14 -3.5083e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 510 511 3.87073 0.130469 -0.150221 0.0050642 0.077371 0.0991197 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 461 511 -8.89067e-13 -3.05972 -0.0937068 0.0612327 -2.04281e-14 -2.93099e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 511 512 3.87676 0.130583 -0.150691 0.00506655 0.0774922 0.0990252 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 462 512 -6.70797e-13 -3.05972 -0.0937068 0.0612327 -1.64313e-14 -2.35367e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 512 513 3.88279 0.130697 -0.15116 0.00506887 0.0776132 0.0989305 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 463 513 -4.51861e-13 -3.05972 -0.0937068 0.0612327 -1.24345e-14 -1.77636e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 513 514 3.88881 0.130809 -0.15163 0.00507116 0.0777341 0.0988356 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 464 514 -2.33591e-13 -3.05972 -0.0937068 0.0612327 -8.43769e-15 -1.19904e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 514 515 3.89483 0.13092 -0.152099 0.00507344 0.0778549 0.0987406 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 465 515 -1.24345e-14 -3.05972 -0.0937068 0.0612327 -4.44089e-15 -6.21725e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 515 516 3.90084 0.13103 -0.15257 0.00507569 0.0779755 0.0986455 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 466 516 2.07834e-13 -3.05972 -0.0937068 0.0612327 0 0 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 516 517 3.90684 0.131138 -0.15304 0.00507792 0.0780961 0.0985502 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 467 517 4.28102e-13 -3.05972 -0.0937068 0.0612327 3.9968e-15 5.77316e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 517 518 3.91284 0.131246 -0.153511 0.00508012 0.0782165 0.0984547 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 468 518 6.55476e-13 -3.05972 -0.0937068 0.0612327 7.99361e-15 1.15463e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 518 519 3.91883 0.131352 -0.153982 0.0050823 0.0783368 0.0983591 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 469 519 8.7752e-13 -3.05972 -0.0937068 0.0612327 1.19904e-14 1.73195e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 519 520 3.92481 0.131457 -0.154453 0.00508446 0.078457 0.0982634 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 470 520 1.09956e-12 -3.05972 -0.0937068 0.0612327 1.64313e-14 2.30926e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 520 521 3.93079 0.131561 -0.154925 0.0050866 0.0785771 0.0981675 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 471 521 1.32516e-12 -3.05972 -0.0937068 0.0612327 2.04281e-14 2.88658e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 521 522 3.93677 0.131664 -0.155396 0.00508871 0.0786971 0.0980715 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 472 522 1.55076e-12 -3.05972 -0.0937068 0.0612327 2.44249e-14 3.4639e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 522 523 3.94274 0.131766 -0.155868 0.0050908 0.0788169 0.0979753 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 473 523 1.77547e-12 -3.05972 -0.0937068 0.0612327 2.88658e-14 4.04121e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 523 524 3.9487 0.131867 -0.156341 0.00509286 0.0789367 0.0978789 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 474 524 2.0024e-12 -3.05972 -0.0937068 0.0612327 3.28626e-14 4.61853e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 524 525 3.95466 0.131966 -0.156813 0.00509491 0.0790563 0.0977825 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 475 525 2.23008e-12 -3.05972 -0.0937068 0.0612327 3.73035e-14 5.19584e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 525 526 3.96061 0.132064 -0.157286 0.00509693 0.0791758 0.0976858 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 476 526 2.45803e-12 -3.05972 -0.0937068 0.0612327 4.13003e-14 5.77316e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 526 527 3.96655 0.132161 -0.157759 0.00509892 0.0792952 0.0975891 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 477 527 2.68585e-12 -3.05972 -0.0937068 0.0612327 4.57412e-14 6.30607e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 527 528 3.97249 0.132257 -0.158232 0.0051009 0.0794144 0.0974921 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 478 528 2.91678e-12 -3.05972 -0.0937068 0.0612327 4.9738e-14 6.88338e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 528 529 3.97842 0.132352 -0.158705 0.00510285 0.0795336 0.0973951 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 479 529 3.14415e-12 -3.05972 -0.0937068 0.0612327 5.41789e-14 7.4607e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 529 530 3.98435 0.132446 -0.159179 0.00510477 0.0796526 0.0972978 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 480 530 3.37508e-12 -3.05972 -0.0937068 0.0612327 5.81757e-14 8.03801e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 530 531 3.99027 0.132538 -0.159653 0.00510668 0.0797715 0.0972005 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 481 531 3.60423e-12 -3.05972 -0.0937068 0.0612327 6.26166e-14 8.61533e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 531 532 3.99618 0.13263 -0.160127 0.00510856 0.0798903 0.097103 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 482 532 3.83871e-12 -3.05972 -0.0937068 0.0612327 6.66134e-14 9.19265e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 532 533 4.00209 0.13272 -0.160601 0.00511042 0.080009 0.0970053 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 483 533 4.06786e-12 -3.05972 -0.0937068 0.0612327 7.10543e-14 9.72555e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 533 534 4.00799 0.132809 -0.161076 0.00511225 0.0801275 0.0969075 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 484 534 4.30411e-12 -3.05972 -0.0937068 0.0612327 7.54952e-14 1.03029e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 534 535 4.01389 0.132897 -0.161551 0.00511406 0.080246 0.0968095 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 485 535 4.53682e-12 -3.05972 -0.0937068 0.0612327 7.99361e-14 1.08802e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 535 536 4.01978 0.132983 -0.162026 0.00511585 0.0803643 0.0967115 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 486 536 4.77396e-12 -3.05972 -0.0937068 0.0612327 8.43769e-14 1.14131e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 536 537 4.02567 0.133069 -0.162501 0.00511761 0.0804825 0.0966132 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 487 537 5.00888e-12 -3.05972 -0.0937068 0.0612327 8.83738e-14 1.19904e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 537 538 4.03154 0.133153 -0.162976 0.00511935 0.0806006 0.0965148 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 488 538 5.24469e-12 -3.05972 -0.0937068 0.0612327 9.28146e-14 1.25233e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 538 539 4.03742 0.133236 -0.163452 0.00512107 0.0807185 0.0964163 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 489 539 5.48095e-12 -3.05972 -0.0937068 0.0612327 9.72555e-14 1.31006e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 539 540 4.04328 0.133318 -0.163928 0.00512277 0.0808363 0.0963176 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 490 540 5.71987e-12 -3.05972 -0.0937068 0.0612327 1.01696e-13 1.36779e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 540 541 4.04914 0.133399 -0.164404 0.00512444 0.0809541 0.0962188 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 491 541 5.95612e-12 -3.05972 -0.0937068 0.0612327 1.06137e-13 1.42109e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 541 542 4.055 0.133479 -0.16488 0.00512608 0.0810716 0.0961198 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 492 542 6.19238e-12 -3.05972 -0.0937068 0.0612327 1.10578e-13 1.47438e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 542 543 4.06085 0.133557 -0.165356 0.00512771 0.0811891 0.0960207 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 493 543 6.43219e-12 -3.05972 -0.0937068 0.0612327 1.15019e-13 1.53211e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 543 544 4.06669 0.133635 -0.165833 0.00512931 0.0813065 0.0959214 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 494 544 6.67377e-12 -3.05972 -0.0937068 0.0612327 1.1946e-13 1.58984e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 544 545 4.07252 0.133711 -0.16631 0.00513089 0.0814237 0.095822 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 495 545 6.91003e-12 -3.05972 -0.0937068 0.0612327 1.23901e-13 1.64313e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 545 546 4.07835 0.133786 -0.166787 0.00513244 0.0815408 0.0957225 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 496 546 7.15517e-12 -3.05972 -0.0937068 0.0612327 1.28342e-13 1.69642e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 546 547 4.08418 0.13386 -0.167264 0.00513397 0.0816578 0.0956228 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 497 547 7.3932e-12 -3.05972 -0.0937068 0.0612327 1.32783e-13 1.75415e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 547 548 4.09 0.133932 -0.167741 0.00513548 0.0817747 0.0955229 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 498 548 7.6561e-12 -3.05972 -0.0937068 0.0612327 1.41664e-13 1.86517e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 548 549 4.09581 0.134004 -0.168219 0.00513696 0.0818914 0.095423 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 499 549 7.88303e-12 -3.05972 -0.0937068 0.0612327 1.42109e-13 1.86517e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 549 550 4.10161 0.134074 -0.168697 0.00513842 0.082008 0.0953228 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 500 550 8.14333e-12 -3.05972 -0.0937068 0.0612327 1.5099e-13 1.9762e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 550 551 4.10741 0.134143 -0.169174 0.00513986 0.0821245 0.0952226 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 501 551 8.37064e-12 -3.05972 -0.0937068 0.0612327 1.5099e-13 1.97176e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 551 552 4.1132 0.134211 -0.169652 0.00514127 0.0822409 0.0951221 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 502 552 8.63398e-12 -3.05972 -0.0937068 0.0612327 1.59872e-13 2.08278e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 552 553 4.11899 0.134278 -0.170131 0.00514266 0.0823572 0.0950216 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 503 553 8.86224e-12 -3.05972 -0.0937068 0.0612327 1.60316e-13 2.08278e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 553 554 4.12477 0.134344 -0.170609 0.00514403 0.0824733 0.0949209 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 504 554 9.12337e-12 -3.05972 -0.0937068 0.0612327 1.69198e-13 2.1938e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 554 555 4.13055 0.134408 -0.171088 0.00514537 0.0825893 0.09482 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 505 555 9.35607e-12 -3.05972 -0.0937068 0.0612327 1.69198e-13 2.18936e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 555 556 4.13632 0.134471 -0.171566 0.00514669 0.0827052 0.094719 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 506 556 9.6172e-12 -3.05972 -0.0937068 0.0612327 1.78524e-13 2.30038e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 556 557 4.14208 0.134534 -0.172045 0.00514799 0.082821 0.0946179 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 507 557 9.85168e-12 -3.05972 -0.0937068 0.0612327 1.78524e-13 2.30038e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 557 558 4.14783 0.134594 -0.172524 0.00514926 0.0829366 0.0945166 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 508 558 1.01146e-11 -3.05972 -0.0937068 0.0612327 1.8785e-13 2.40696e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 558 559 4.15358 0.134654 -0.173003 0.00515051 0.0830521 0.0944152 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 509 559 1.03473e-11 -3.05972 -0.0937068 0.0612327 1.8785e-13 2.40696e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 559 560 4.15933 0.134713 -0.173482 0.00515174 0.0831675 0.0943136 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 510 560 1.06137e-11 -3.05972 -0.0937068 0.0612327 1.97176e-13 2.51354e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 560 561 4.16506 0.13477 -0.173962 0.00515294 0.0832828 0.0942119 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 511 561 1.06306e-11 -3.05972 -0.0937068 0.0612327 1.97176e-13 2.51354e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 561 562 4.17079 0.134827 -0.174441 0.00515412 0.0833979 0.0941101 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 512 562 1.0645e-11 -3.05972 -0.0937068 0.0612327 1.9762e-13 2.5091e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 562 563 4.17652 0.134882 -0.174921 0.00515527 0.0835129 0.0940081 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 513 563 1.0659e-11 -3.05972 -0.0937068 0.0612327 1.98064e-13 2.5091e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 563 564 4.18224 0.134936 -0.175401 0.00515641 0.0836278 0.093906 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 514 564 1.06732e-11 -3.05972 -0.0937068 0.0612327 1.98064e-13 2.50466e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 564 565 4.18795 0.134988 -0.175881 0.00515751 0.0837426 0.0938037 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 515 565 1.06866e-11 -3.05972 -0.0937068 0.0612327 1.98508e-13 2.50466e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 565 566 4.19366 0.13504 -0.176361 0.0051586 0.0838572 0.0937013 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 516 566 1.07008e-11 -3.05972 -0.0937068 0.0612327 1.98952e-13 2.50022e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 566 567 4.19936 0.13509 -0.176841 0.00515966 0.0839718 0.0935987 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 517 567 1.07168e-11 -3.05972 -0.0937068 0.0612327 1.99396e-13 2.50022e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 567 568 4.20505 0.135139 -0.177321 0.0051607 0.0840862 0.093496 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 518 568 1.07327e-11 -3.05972 -0.0937068 0.0612327 1.99396e-13 2.49578e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 568 569 4.21074 0.135187 -0.177802 0.00516171 0.0842004 0.0933932 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 519 569 1.07434e-11 -3.05972 -0.0937068 0.0612327 1.9984e-13 2.49134e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 569 570 4.21642 0.135234 -0.178282 0.0051627 0.0843146 0.0932902 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 520 570 1.07647e-11 -3.05972 -0.0937068 0.0612327 1.9984e-13 2.49134e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 570 571 4.22209 0.13528 -0.178763 0.00516367 0.0844286 0.0931871 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 521 571 1.07789e-11 -3.05972 -0.0937068 0.0612327 2.00284e-13 2.4869e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 571 572 4.22776 0.135324 -0.179244 0.00516461 0.0845425 0.0930838 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 522 572 1.07931e-11 -3.05972 -0.0937068 0.0612327 2.00728e-13 2.4869e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 572 573 4.23342 0.135368 -0.179725 0.00516553 0.0846563 0.0929804 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 523 573 1.08029e-11 -3.05972 -0.0937068 0.0612327 2.01172e-13 2.48246e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 573 574 4.23908 0.13541 -0.180206 0.00516642 0.0847699 0.0928769 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 524 574 1.08185e-11 -3.05972 -0.0937068 0.0612327 2.01172e-13 2.48246e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 574 575 4.24472 0.135451 -0.180687 0.0051673 0.0848834 0.0927732 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 525 575 1.08331e-11 -3.05972 -0.0937068 0.0612327 2.01617e-13 2.47802e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 575 576 4.25037 0.135491 -0.181168 0.00516814 0.0849968 0.0926694 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 526 576 1.08482e-11 -3.05972 -0.0937068 0.0612327 2.02061e-13 2.47802e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 576 577 4.256 0.135529 -0.181649 0.00516897 0.0851101 0.0925654 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 527 577 1.08651e-11 -3.05972 -0.0937068 0.0612327 2.02061e-13 2.47358e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 577 578 4.26163 0.135567 -0.182131 0.00516977 0.0852232 0.0924613 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 528 578 1.08731e-11 -3.05972 -0.0937068 0.0612327 2.02505e-13 2.46914e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 578 579 4.26726 0.135603 -0.182612 0.00517055 0.0853362 0.0923571 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 529 579 1.08926e-11 -3.05972 -0.0937068 0.0612327 2.02949e-13 2.46914e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 579 580 4.27287 0.135638 -0.183094 0.0051713 0.0854491 0.0922527 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 530 580 1.09051e-11 -3.05972 -0.0937068 0.0612327 2.02949e-13 2.4647e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 580 581 4.27849 0.135672 -0.183575 0.00517203 0.0855618 0.0921481 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 531 581 1.09193e-11 -3.05972 -0.0937068 0.0612327 2.03393e-13 2.4647e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 581 582 4.28409 0.135705 -0.184057 0.00517274 0.0856745 0.0920435 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 532 582 1.0937e-11 -3.05972 -0.0937068 0.0612327 2.03837e-13 2.46025e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 582 583 4.28969 0.135736 -0.184539 0.00517342 0.085787 0.0919387 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 533 583 1.09495e-11 -3.05972 -0.0937068 0.0612327 2.04281e-13 2.46025e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 583 584 4.29528 0.135766 -0.185021 0.00517408 0.0858993 0.0918337 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 534 584 1.09637e-11 -3.05972 -0.0937068 0.0612327 2.04281e-13 2.45581e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 584 585 4.30086 0.135796 -0.185503 0.00517472 0.0860116 0.0917287 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 535 585 1.09761e-11 -3.05972 -0.0937068 0.0612327 2.04725e-13 2.45137e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 585 586 4.30644 0.135824 -0.185985 0.00517533 0.0861237 0.0916234 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 536 586 1.09912e-11 -3.05972 -0.0937068 0.0612327 2.04725e-13 2.45137e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 586 587 4.31201 0.13585 -0.186467 0.00517592 0.0862357 0.0915181 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 537 587 1.10045e-11 -3.05972 -0.0937068 0.0612327 2.05169e-13 2.44693e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 587 588 4.31758 0.135876 -0.186949 0.00517648 0.0863475 0.0914126 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 538 588 1.10183e-11 -3.05972 -0.0937068 0.0612327 2.05613e-13 2.44693e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 588 589 4.32314 0.135901 -0.187431 0.00517702 0.0864593 0.0913069 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 539 589 1.1033e-11 -3.05972 -0.0937068 0.0612327 2.06057e-13 2.44249e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 589 590 4.32869 0.135924 -0.187914 0.00517754 0.0865709 0.0912012 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 540 590 1.10489e-11 -3.05972 -0.0937068 0.0612327 2.06057e-13 2.44249e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 590 591 4.33424 0.135946 -0.188396 0.00517803 0.0866823 0.0910953 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 541 591 1.10596e-11 -3.05972 -0.0937068 0.0612327 2.06501e-13 2.43805e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 591 592 4.33978 0.135967 -0.188878 0.0051785 0.0867937 0.0909892 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 542 592 1.10738e-11 -3.05972 -0.0937068 0.0612327 2.06946e-13 2.43805e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 592 593 4.34531 0.135986 -0.189361 0.00517895 0.0869049 0.090883 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 543 593 1.10933e-11 -3.05972 -0.0937068 0.0612327 2.06946e-13 2.43361e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 593 594 4.35084 0.136005 -0.189843 0.00517937 0.087016 0.0907767 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 544 594 1.11058e-11 -3.05972 -0.0937068 0.0612327 2.0739e-13 2.42917e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 594 595 4.35636 0.136022 -0.190326 0.00517977 0.0871269 0.0906702 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 545 595 1.112e-11 -3.05972 -0.0937068 0.0612327 2.07834e-13 2.42917e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 595 596 4.36187 0.136039 -0.190808 0.00518014 0.0872378 0.0905636 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 546 596 1.11289e-11 -3.05972 -0.0937068 0.0612327 2.07834e-13 2.42473e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 596 597 4.36738 0.136054 -0.191291 0.00518049 0.0873484 0.0904569 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 547 597 1.11466e-11 -3.05972 -0.0937068 0.0612327 2.08278e-13 2.42473e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 597 598 4.37288 0.136067 -0.191774 0.00518082 0.087459 0.09035 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 548 598 1.11591e-11 -3.05972 -0.0937068 0.0612327 2.08722e-13 2.42029e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 598 599 4.37837 0.13608 -0.192256 0.00518113 0.0875694 0.090243 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 549 599 1.11724e-11 -3.05972 -0.0937068 0.0612327 2.08722e-13 2.42029e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 599 600 4.38386 0.136091 -0.192739 0.00518141 0.0876797 0.0901359 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 550 600 1.11875e-11 -3.05972 -0.0937068 0.0612327 2.09166e-13 2.41585e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 600 601 4.38934 0.136102 -0.193222 0.00518166 0.0877899 0.0900286 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 551 601 1.12017e-11 -3.05972 -0.0937068 0.0612327 2.0961e-13 2.4114e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 601 602 4.39481 0.136111 -0.193704 0.00518189 0.0878999 0.0899211 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 552 602 1.12141e-11 -3.05972 -0.0937068 0.0612327 2.0961e-13 2.4114e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 602 603 4.40028 0.136119 -0.194187 0.0051821 0.0880099 0.0898136 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 553 603 1.12266e-11 -3.05972 -0.0937068 0.0612327 2.10054e-13 2.40696e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 603 604 4.40574 0.136125 -0.19467 0.00518229 0.0881196 0.0897059 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 554 604 1.12479e-11 -3.05972 -0.0937068 0.0612327 2.10498e-13 2.40696e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 604 605 4.4112 0.136131 -0.195153 0.00518245 0.0882293 0.0895981 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 555 605 1.12568e-11 -3.05972 -0.0937068 0.0612327 2.10498e-13 2.40252e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 605 606 4.41664 0.136135 -0.195636 0.00518259 0.0883388 0.0894901 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 556 606 1.12692e-11 -3.05972 -0.0937068 0.0612327 2.10942e-13 2.39808e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 606 607 4.42209 0.136138 -0.196118 0.0051827 0.0884482 0.089382 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 557 607 1.12799e-11 -3.05972 -0.0937068 0.0612327 2.11386e-13 2.39808e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 607 608 4.42752 0.13614 -0.196601 0.00518279 0.0885574 0.0892738 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 558 608 1.13012e-11 -3.05972 -0.0937068 0.0612327 2.11386e-13 2.39364e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 608 609 4.43295 0.136141 -0.197084 0.00518286 0.0886665 0.0891654 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 559 609 1.13118e-11 -3.05972 -0.0937068 0.0612327 2.11831e-13 2.39364e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 609 610 4.43837 0.136141 -0.197567 0.0051829 0.0887755 0.0890569 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 560 610 1.13278e-11 -3.05972 -0.0937068 0.0612327 2.12275e-13 2.3892e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 610 611 4.44378 0.136139 -0.19805 0.00518292 0.0888844 0.0889482 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 561 611 1.13412e-11 -3.05972 -0.0937068 0.0612327 2.12275e-13 2.3892e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 611 612 4.44919 0.136136 -0.198533 0.00518291 0.0889931 0.0888395 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 562 612 1.13531e-11 -3.05972 -0.0937068 0.0612327 2.12719e-13 2.38476e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 612 613 4.45459 0.136133 -0.199015 0.00518289 0.0891017 0.0887306 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 563 613 1.13678e-11 -3.05972 -0.0937068 0.0612327 2.13163e-13 2.38032e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 613 614 4.45999 0.136127 -0.199498 0.00518283 0.0892101 0.0886215 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 564 614 1.1382e-11 -3.05972 -0.0937068 0.0612327 2.13163e-13 2.38032e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 614 615 4.46538 0.136121 -0.199981 0.00518276 0.0893185 0.0885123 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 565 615 1.13953e-11 -3.05972 -0.0937068 0.0612327 2.13607e-13 2.37588e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 615 616 4.47076 0.136114 -0.200464 0.00518266 0.0894267 0.088403 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 566 616 1.1406e-11 -3.05972 -0.0937068 0.0612327 2.13607e-13 2.37588e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 616 617 4.47613 0.136105 -0.200947 0.00518253 0.0895347 0.0882936 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 567 617 1.1422e-11 -3.05972 -0.0937068 0.0612327 2.14051e-13 2.37144e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 617 618 4.4815 0.136095 -0.201429 0.00518239 0.0896426 0.088184 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 568 618 1.14326e-11 -3.05972 -0.0937068 0.0612327 2.14495e-13 2.367e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 618 619 4.48686 0.136084 -0.201912 0.00518221 0.0897504 0.0880743 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 569 619 1.14468e-11 -3.05972 -0.0937068 0.0612327 2.14939e-13 2.367e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 619 620 4.49221 0.136072 -0.202395 0.00518202 0.0898581 0.0879644 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 570 620 1.14593e-11 -3.05972 -0.0937068 0.0612327 2.14939e-13 2.36255e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 620 621 4.49756 0.136059 -0.202877 0.0051818 0.0899656 0.0878544 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 571 621 1.14735e-11 -3.05972 -0.0937068 0.0612327 2.15383e-13 2.36255e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 621 622 4.5029 0.136044 -0.20336 0.00518156 0.090073 0.0877443 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 572 622 1.14895e-11 -3.05972 -0.0937068 0.0612327 2.15383e-13 2.35811e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 622 623 4.50824 0.136028 -0.203843 0.00518129 0.0901802 0.0876341 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 573 623 1.15072e-11 -3.05972 -0.0937068 0.0612327 2.15827e-13 2.35367e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 623 624 4.51356 0.136011 -0.204325 0.005181 0.0902874 0.0875237 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 574 624 1.15161e-11 -3.05972 -0.0937068 0.0612327 2.16271e-13 2.35367e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 624 625 4.51888 0.135993 -0.204808 0.00518069 0.0903943 0.0874132 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 575 625 1.15313e-11 -3.05972 -0.0937068 0.0612327 2.16271e-13 2.34923e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 625 626 4.5242 0.135974 -0.20529 0.00518035 0.0905012 0.0873025 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 576 626 1.15428e-11 -3.05972 -0.0937068 0.0612327 2.16716e-13 2.34923e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 626 627 4.52951 0.135953 -0.205772 0.00517999 0.0906079 0.0871918 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 577 627 1.15552e-11 -3.05972 -0.0937068 0.0612327 2.1716e-13 2.34479e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 627 628 4.53481 0.135932 -0.206255 0.00517961 0.0907145 0.0870808 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 578 628 1.15765e-11 -3.05972 -0.0937068 0.0612327 2.1716e-13 2.34035e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 628 629 4.5401 0.135909 -0.206737 0.0051792 0.0908209 0.0869698 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 579 629 1.15836e-11 -3.05972 -0.0937068 0.0612327 2.17604e-13 2.34035e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 629 630 4.54539 0.135885 -0.207219 0.00517877 0.0909272 0.0868586 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 580 630 1.15961e-11 -3.05972 -0.0937068 0.0612327 2.18048e-13 2.33591e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 630 631 4.55067 0.13586 -0.207702 0.00517831 0.0910334 0.0867473 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 581 631 1.16174e-11 -3.05972 -0.0937068 0.0612327 2.18048e-13 2.33591e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 631 632 4.55594 0.135833 -0.208184 0.00517783 0.0911394 0.0866359 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 582 632 1.16245e-11 -3.05972 -0.0937068 0.0612327 2.18492e-13 2.33147e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 632 633 4.5612 0.135806 -0.208666 0.00517733 0.0912453 0.0865243 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 583 633 1.1644e-11 -3.05972 -0.0937068 0.0612327 2.18492e-13 2.32703e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 633 634 4.56646 0.135777 -0.209148 0.0051768 0.0913511 0.0864126 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 584 634 1.16529e-11 -3.05972 -0.0937068 0.0612327 2.18936e-13 2.32703e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 634 635 4.57172 0.135747 -0.20963 0.00517625 0.0914567 0.0863008 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 585 635 1.16653e-11 -3.05972 -0.0937068 0.0612327 2.1938e-13 2.32259e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 635 636 4.57696 0.135716 -0.210111 0.00517567 0.0915622 0.0861888 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 586 636 1.16787e-11 -3.05972 -0.0937068 0.0612327 2.1938e-13 2.32259e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 636 637 4.5822 0.135684 -0.210593 0.00517507 0.0916676 0.0860767 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 587 637 1.16929e-11 -3.05972 -0.0937068 0.0612327 2.19824e-13 2.31815e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 637 638 4.58743 0.13565 -0.211075 0.00517445 0.0917728 0.0859645 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 588 638 1.17057e-11 -3.05972 -0.0937068 0.0612327 2.20268e-13 2.3137e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 638 639 4.59266 0.135616 -0.211556 0.00517381 0.0918778 0.0858521 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 589 639 1.17195e-11 -3.05972 -0.0937068 0.0612327 2.20268e-13 2.3137e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 639 640 4.59787 0.13558 -0.212038 0.00517314 0.0919828 0.0857397 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 590 640 1.17293e-11 -3.05972 -0.0937068 0.0612327 2.20712e-13 2.30926e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 640 641 4.60309 0.135543 -0.212519 0.00517244 0.0920876 0.085627 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 591 641 1.17453e-11 -3.05972 -0.0937068 0.0612327 2.21156e-13 2.30926e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 641 642 4.60829 0.135505 -0.213001 0.00517173 0.0921923 0.0855143 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 592 642 1.1763e-11 -3.05972 -0.0937068 0.0612327 2.21156e-13 2.30482e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 642 643 4.61349 0.135465 -0.213482 0.00517099 0.0922968 0.0854014 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 593 643 1.17701e-11 -3.05972 -0.0937068 0.0612327 2.21601e-13 2.30038e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 643 644 4.61868 0.135425 -0.213963 0.00517022 0.0924012 0.0852884 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 594 644 1.17879e-11 -3.05972 -0.0937068 0.0612327 2.22045e-13 2.30038e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 644 645 4.62386 0.135383 -0.214444 0.00516943 0.0925054 0.0851753 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 595 645 1.18021e-11 -3.05972 -0.0937068 0.0612327 2.22045e-13 2.29594e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 645 646 4.62904 0.13534 -0.214925 0.00516862 0.0926095 0.085062 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 596 646 1.18128e-11 -3.05972 -0.0937068 0.0612327 2.22489e-13 2.29594e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 646 647 4.63421 0.135296 -0.215406 0.00516779 0.0927135 0.0849486 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 597 647 1.1827e-11 -3.05972 -0.0937068 0.0612327 2.22489e-13 2.2915e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 647 648 4.63937 0.135251 -0.215887 0.00516693 0.0928174 0.0848351 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 598 648 1.18394e-11 -3.05972 -0.0937068 0.0612327 2.22933e-13 2.28706e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 648 649 4.64453 0.135204 -0.216367 0.00516604 0.0929211 0.0847214 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 599 649 1.1851e-11 -3.05972 -0.0937068 0.0612327 2.23377e-13 2.28706e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 649 650 4.64967 0.135157 -0.216848 0.00516514 0.0930246 0.0846077 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 600 650 1.18644e-11 -3.05972 -0.0937068 0.0612327 2.23377e-13 2.28262e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 650 651 4.65482 0.135108 -0.217328 0.00516421 0.093128 0.0844938 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 601 651 1.18785e-11 -3.05972 -0.0937068 0.0612327 2.23821e-13 2.27818e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 651 652 4.65995 0.135058 -0.217808 0.00516325 0.0932313 0.0843797 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 602 652 1.18892e-11 -3.05972 -0.0937068 0.0612327 2.24265e-13 2.27818e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 652 653 4.66508 0.135007 -0.218288 0.00516228 0.0933345 0.0842656 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 603 653 1.19034e-11 -3.05972 -0.0937068 0.0612327 2.24265e-13 2.27374e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 653 654 4.6702 0.134954 -0.218768 0.00516128 0.0934375 0.0841513 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 604 654 1.19122e-11 -3.05972 -0.0937068 0.0612327 2.24709e-13 2.27374e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 654 655 4.67531 0.134901 -0.219248 0.00516025 0.0935403 0.0840368 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 605 655 1.193e-11 -3.05972 -0.0937068 0.0612327 2.24709e-13 2.2693e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 655 656 4.68042 0.134846 -0.219728 0.0051592 0.0936431 0.0839223 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 606 656 1.19407e-11 -3.05972 -0.0937068 0.0612327 2.25153e-13 2.26485e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 656 657 4.68552 0.13479 -0.220208 0.00515813 0.0937456 0.0838076 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 607 657 1.19584e-11 -3.05972 -0.0937068 0.0612327 2.25597e-13 2.26485e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 657 658 4.69061 0.134733 -0.220687 0.00515704 0.0938481 0.0836928 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 608 658 1.19673e-11 -3.05972 -0.0937068 0.0612327 2.25597e-13 2.26041e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 658 659 4.6957 0.134675 -0.221166 0.00515592 0.0939504 0.0835779 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 609 659 1.19815e-11 -3.05972 -0.0937068 0.0612327 2.26041e-13 2.26041e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 659 660 4.70078 0.134616 -0.221646 0.00515477 0.0940526 0.0834628 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 610 660 1.1994e-11 -3.05972 -0.0937068 0.0612327 2.26041e-13 2.25597e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 660 661 4.70585 0.134555 -0.222125 0.00515361 0.0941546 0.0833476 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 611 661 1.20064e-11 -3.05972 -0.0937068 0.0612327 2.26485e-13 2.25153e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 661 662 4.71091 0.134494 -0.222603 0.00515242 0.0942565 0.0832323 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 612 662 1.20206e-11 -3.05972 -0.0937068 0.0612327 2.2693e-13 2.25153e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 662 663 4.71597 0.134431 -0.223082 0.0051512 0.0943582 0.0831169 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 613 663 1.20335e-11 -3.05972 -0.0937068 0.0612327 2.2693e-13 2.24709e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 663 664 4.72102 0.134367 -0.223561 0.00514997 0.0944598 0.0830013 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 614 664 1.20464e-11 -3.05972 -0.0937068 0.0612327 2.27374e-13 2.24265e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 664 665 4.72606 0.134301 -0.224039 0.0051487 0.0945613 0.0828856 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 615 665 1.20579e-11 -3.05972 -0.0937068 0.0612327 2.27818e-13 2.24265e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 665 666 4.7311 0.134235 -0.224517 0.00514742 0.0946626 0.0827698 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 616 666 1.20721e-11 -3.05972 -0.0937068 0.0612327 2.27818e-13 2.23821e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 666 667 4.73613 0.134167 -0.224995 0.00514611 0.0947638 0.0826539 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 617 667 1.20863e-11 -3.05972 -0.0937068 0.0612327 2.28262e-13 2.23821e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 667 668 4.74115 0.134099 -0.225473 0.00514478 0.0948648 0.0825378 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 618 668 1.2097e-11 -3.05972 -0.0937068 0.0612327 2.28262e-13 2.23377e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 668 669 4.74617 0.134029 -0.225951 0.00514343 0.0949657 0.0824216 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 619 669 1.21076e-11 -3.05972 -0.0937068 0.0612327 2.28706e-13 2.22933e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 669 670 4.75117 0.133958 -0.226429 0.00514205 0.0950665 0.0823053 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 620 670 1.2129e-11 -3.05972 -0.0937068 0.0612327 2.2915e-13 2.22933e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 670 671 4.75617 0.133886 -0.226906 0.00514064 0.0951671 0.0821889 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 621 671 1.21396e-11 -3.05972 -0.0937068 0.0612327 2.2915e-13 2.22489e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 671 672 4.76117 0.133812 -0.227383 0.00513922 0.0952675 0.0820723 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 622 672 1.21538e-11 -3.05972 -0.0937068 0.0612327 2.29594e-13 2.22045e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 672 673 4.76615 0.133738 -0.22786 0.00513777 0.0953679 0.0819556 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 623 673 1.21609e-11 -3.05972 -0.0937068 0.0612327 2.30038e-13 2.22045e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 673 674 4.77113 0.133662 -0.228337 0.0051363 0.095468 0.0818388 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 624 674 1.2176e-11 -3.05972 -0.0937068 0.0612327 2.30038e-13 2.21601e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 674 675 4.77611 0.133585 -0.228814 0.0051348 0.0955681 0.0817219 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 625 675 1.21863e-11 -3.05972 -0.0937068 0.0612327 2.30482e-13 2.21156e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 675 676 4.78107 0.133507 -0.22929 0.00513328 0.095668 0.0816048 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 626 676 1.21991e-11 -3.05972 -0.0937068 0.0612327 2.30482e-13 2.21156e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 676 677 4.78603 0.133427 -0.229767 0.00513174 0.0957677 0.0814876 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 627 677 1.22107e-11 -3.05972 -0.0937068 0.0612327 2.30926e-13 2.20712e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 677 678 4.79098 0.133347 -0.230243 0.00513017 0.0958674 0.0813703 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 628 678 1.22231e-11 -3.05972 -0.0937068 0.0612327 2.3137e-13 2.20712e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 678 679 4.79592 0.133265 -0.230719 0.00512858 0.0959668 0.0812528 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 629 679 1.22373e-11 -3.05972 -0.0937068 0.0612327 2.3137e-13 2.20268e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 679 680 4.80086 0.133183 -0.231194 0.00512697 0.0960661 0.0811353 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 630 680 1.22462e-11 -3.05972 -0.0937068 0.0612327 2.31815e-13 2.19824e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 680 681 4.80579 0.133099 -0.23167 0.00512533 0.0961653 0.0810176 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 631 681 1.2264e-11 -3.05972 -0.0937068 0.0612327 2.31815e-13 2.19824e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 681 682 4.81071 0.133014 -0.232145 0.00512367 0.0962644 0.0808998 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 632 682 1.22746e-11 -3.05972 -0.0937068 0.0612327 2.32259e-13 2.1938e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 682 683 4.81562 0.132927 -0.23262 0.00512199 0.0963633 0.0807819 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 633 683 1.22853e-11 -3.05972 -0.0937068 0.0612327 2.32703e-13 2.1938e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 683 684 4.82053 0.13284 -0.233095 0.00512028 0.096462 0.0806638 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 634 684 1.22977e-11 -3.05972 -0.0937068 0.0612327 2.32703e-13 2.18936e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 684 685 4.82543 0.132751 -0.23357 0.00511855 0.0965606 0.0805456 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 635 685 1.23137e-11 -3.05972 -0.0937068 0.0612327 2.33147e-13 2.18492e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 685 686 4.83032 0.132662 -0.234044 0.00511679 0.0966591 0.0804273 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 636 686 1.23253e-11 -3.05972 -0.0937068 0.0612327 2.33147e-13 2.18048e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 686 687 4.83521 0.132571 -0.234518 0.00511501 0.0967574 0.0803089 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 637 687 1.23368e-11 -3.05972 -0.0937068 0.0612327 2.33591e-13 2.18048e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 687 688 4.84009 0.132479 -0.234992 0.00511321 0.0968556 0.0801904 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 638 688 1.23492e-11 -3.05972 -0.0937068 0.0612327 2.34035e-13 2.17604e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 688 689 4.84496 0.132386 -0.235466 0.00511139 0.0969536 0.0800717 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 639 689 1.23608e-11 -3.05972 -0.0937068 0.0612327 2.34035e-13 2.1716e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 689 690 4.84982 0.132291 -0.23594 0.00510954 0.0970515 0.0799529 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 640 690 1.23777e-11 -3.05972 -0.0937068 0.0612327 2.34479e-13 2.1716e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 690 691 4.85468 0.132196 -0.236413 0.00510767 0.0971492 0.079834 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 641 691 1.23901e-11 -3.05972 -0.0937068 0.0612327 2.34479e-13 2.16716e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 691 692 4.85953 0.132099 -0.236886 0.00510578 0.0972468 0.079715 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 642 692 1.23954e-11 -3.05972 -0.0937068 0.0612327 2.34923e-13 2.16716e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 692 693 4.86437 0.132001 -0.237359 0.00510386 0.0973443 0.0795958 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 643 693 1.24096e-11 -3.05972 -0.0937068 0.0612327 2.35367e-13 2.16271e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 693 694 4.86921 0.131902 -0.237831 0.00510192 0.0974416 0.0794765 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 644 694 1.24238e-11 -3.05972 -0.0937068 0.0612327 2.35367e-13 2.15827e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 694 695 4.87403 0.131802 -0.238304 0.00509995 0.0975387 0.0793572 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 645 695 1.24381e-11 -3.05972 -0.0937068 0.0612327 2.35811e-13 2.15827e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 695 696 4.87885 0.131701 -0.238776 0.00509796 0.0976357 0.0792376 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 646 696 1.24505e-11 -3.05972 -0.0937068 0.0612327 2.35811e-13 2.15383e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 696 697 4.88367 0.131598 -0.239248 0.00509595 0.0977326 0.079118 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 647 697 1.24611e-11 -3.05972 -0.0937068 0.0612327 2.36255e-13 2.14939e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 697 698 4.88847 0.131494 -0.239719 0.00509392 0.0978293 0.0789982 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 648 698 1.247e-11 -3.05972 -0.0937068 0.0612327 2.367e-13 2.14939e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 698 699 4.89327 0.13139 -0.240191 0.00509186 0.0979259 0.0788784 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 649 699 1.24833e-11 -3.05972 -0.0937068 0.0612327 2.367e-13 2.14495e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 699 700 4.89806 0.131284 -0.240662 0.00508978 0.0980223 0.0787584 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 650 700 1.24968e-11 -3.05972 -0.0937068 0.0612327 2.37144e-13 2.14051e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 700 701 4.90284 0.131177 -0.241132 0.00508768 0.0981186 0.0786383 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 651 701 1.25091e-11 -3.05972 -0.0937068 0.0612327 2.37144e-13 2.14051e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 701 702 4.90762 0.131068 -0.241603 0.00508555 0.0982147 0.078518 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 652 702 1.25233e-11 -3.05972 -0.0937068 0.0612327 2.37588e-13 2.13607e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 702 703 4.91239 0.130959 -0.242073 0.0050834 0.0983107 0.0783977 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 653 703 1.25358e-11 -3.05972 -0.0937068 0.0612327 2.38032e-13 2.13163e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 703 704 4.91715 0.130848 -0.242543 0.00508122 0.0984065 0.0782772 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 654 704 1.255e-11 -3.05972 -0.0937068 0.0612327 2.38032e-13 2.13163e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 704 705 4.9219 0.130737 -0.243013 0.00507903 0.0985022 0.0781566 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 655 705 1.25588e-11 -3.05972 -0.0937068 0.0612327 2.38476e-13 2.12719e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 705 706 4.92665 0.130624 -0.243482 0.00507681 0.0985978 0.0780359 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 656 706 1.25659e-11 -3.05972 -0.0937068 0.0612327 2.3892e-13 2.12275e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 706 707 4.93139 0.13051 -0.243952 0.00507456 0.0986932 0.0779151 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 657 707 1.25766e-11 -3.05972 -0.0937068 0.0612327 2.3892e-13 2.12275e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 707 708 4.93612 0.130395 -0.244421 0.0050723 0.0987884 0.0777941 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 658 708 1.25944e-11 -3.05972 -0.0937068 0.0612327 2.39364e-13 2.11831e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 708 709 4.94085 0.130278 -0.244889 0.00507001 0.0988835 0.077673 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 659 709 1.26033e-11 -3.05972 -0.0937068 0.0612327 2.39364e-13 2.11386e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 709 710 4.94556 0.130161 -0.245357 0.00506769 0.0989785 0.0775519 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 660 710 1.26192e-11 -3.05972 -0.0937068 0.0612327 2.39808e-13 2.11386e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 710 711 4.95027 0.130042 -0.245826 0.00506536 0.0990733 0.0774305 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 661 711 1.26326e-11 -3.05972 -0.0937068 0.0612327 2.39808e-13 2.10942e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 711 712 4.95498 0.129923 -0.246293 0.005063 0.0991679 0.0773091 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 662 712 1.26423e-11 -3.05972 -0.0937068 0.0612327 2.40252e-13 2.10498e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 712 713 4.95967 0.129802 -0.246761 0.00506062 0.0992624 0.0771876 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 663 713 1.26539e-11 -3.05972 -0.0937068 0.0612327 2.40252e-13 2.10498e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 713 714 4.96436 0.12968 -0.247228 0.00505821 0.0993568 0.0770659 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 664 714 1.26645e-11 -3.05972 -0.0937068 0.0612327 2.40696e-13 2.10054e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 714 715 4.96904 0.129556 -0.247695 0.00505578 0.099451 0.0769441 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 665 715 1.26779e-11 -3.05972 -0.0937068 0.0612327 2.4114e-13 2.0961e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 715 716 4.97371 0.129432 -0.248161 0.00505333 0.0995451 0.0768223 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 666 716 1.26921e-11 -3.05972 -0.0937068 0.0612327 2.4114e-13 2.0961e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 716 717 4.97838 0.129307 -0.248628 0.00505086 0.099639 0.0767002 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 667 717 1.26974e-11 -3.05972 -0.0937068 0.0612327 2.41585e-13 2.09166e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 717 718 4.98303 0.12918 -0.249094 0.00504836 0.0997328 0.0765781 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 668 718 1.27116e-11 -3.05972 -0.0937068 0.0612327 2.42029e-13 2.09166e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 718 719 4.98768 0.129052 -0.249559 0.00504584 0.0998264 0.0764559 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 669 719 1.27258e-11 -3.05972 -0.0937068 0.0612327 2.42029e-13 2.08722e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 719 720 4.99233 0.128923 -0.250024 0.0050433 0.0999198 0.0763335 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 670 720 1.27329e-11 -3.05972 -0.0937068 0.0612327 2.42473e-13 2.08278e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 720 721 4.99696 0.128793 -0.250489 0.00504073 0.100013 0.076211 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 671 721 1.27436e-11 -3.05972 -0.0937068 0.0612327 2.42473e-13 2.07834e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 721 722 5.00159 0.128662 -0.250954 0.00503814 0.100106 0.0760884 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 672 722 1.27578e-11 -3.05972 -0.0937068 0.0612327 2.42917e-13 2.07834e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 722 723 5.00621 0.12853 -0.251418 0.00503553 0.100199 0.0759657 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 673 723 1.27702e-11 -3.05972 -0.0937068 0.0612327 2.42917e-13 2.0739e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 723 724 5.01082 0.128397 -0.251883 0.00503289 0.100292 0.0758429 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 674 724 1.27844e-11 -3.05972 -0.0937068 0.0612327 2.43361e-13 2.06946e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 724 725 5.01543 0.128262 -0.252346 0.00503023 0.100385 0.07572 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 675 725 1.27956e-11 -3.05972 -0.0937068 0.0612327 2.43361e-13 2.06946e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 725 726 5.02002 0.128126 -0.25281 0.00502755 0.100477 0.0755969 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 676 726 1.28075e-11 -3.05972 -0.0937068 0.0612327 2.43805e-13 2.06501e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 726 727 5.02461 0.127989 -0.253273 0.00502485 0.10057 0.0754737 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 677 727 1.28182e-11 -3.05972 -0.0937068 0.0612327 2.43805e-13 2.06057e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 727 728 5.0292 0.127851 -0.253735 0.00502212 0.100662 0.0753505 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 678 728 1.28342e-11 -3.05972 -0.0937068 0.0612327 2.44249e-13 2.06057e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 728 729 5.03377 0.127712 -0.254198 0.00501937 0.100754 0.0752271 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 679 729 1.28466e-11 -3.05972 -0.0937068 0.0612327 2.44249e-13 2.05613e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 729 730 5.03834 0.127572 -0.25466 0.0050166 0.100846 0.0751035 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 680 730 1.28502e-11 -3.05972 -0.0937068 0.0612327 2.44693e-13 2.05169e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 730 731 5.0429 0.127431 -0.255121 0.0050138 0.100938 0.0749799 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 681 731 1.28608e-11 -3.05972 -0.0937068 0.0612327 2.45137e-13 2.05169e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 731 732 5.04745 0.127288 -0.255583 0.00501099 0.10103 0.0748562 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 682 732 1.28786e-11 -3.05972 -0.0937068 0.0612327 2.45137e-13 2.04725e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 732 733 5.05199 0.127145 -0.256044 0.00500815 0.101121 0.0747323 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 683 733 1.28892e-11 -3.05972 -0.0937068 0.0612327 2.45581e-13 2.04281e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 733 734 5.05653 0.127 -0.256504 0.00500528 0.101213 0.0746083 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 684 734 1.28999e-11 -3.05972 -0.0937068 0.0612327 2.45581e-13 2.04281e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 734 735 5.06106 0.126854 -0.256965 0.0050024 0.101304 0.0744842 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 685 735 1.29141e-11 -3.05972 -0.0937068 0.0612327 2.46025e-13 2.03837e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 735 736 5.06558 0.126707 -0.257425 0.00499949 0.101395 0.07436 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 686 736 1.29221e-11 -3.05972 -0.0937068 0.0612327 2.4647e-13 2.03393e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 736 737 5.0701 0.126559 -0.257884 0.00499655 0.101486 0.0742357 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 687 737 1.2935e-11 -3.05972 -0.0937068 0.0612327 2.4647e-13 2.03393e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 737 738 5.0746 0.126409 -0.258343 0.0049936 0.101577 0.0741113 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 688 738 1.29461e-11 -3.05972 -0.0937068 0.0612327 2.46914e-13 2.02949e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 738 739 5.0791 0.126259 -0.258802 0.00499062 0.101667 0.0739868 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 689 739 1.29576e-11 -3.05972 -0.0937068 0.0612327 2.46914e-13 2.02505e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 739 740 5.08359 0.126108 -0.259261 0.00498762 0.101758 0.0738621 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 690 740 1.29674e-11 -3.05972 -0.0937068 0.0612327 2.47358e-13 2.02505e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 740 741 5.08808 0.125955 -0.259719 0.0049846 0.101848 0.0737374 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 691 741 1.29781e-11 -3.05972 -0.0937068 0.0612327 2.47358e-13 2.02061e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 741 742 5.09255 0.125801 -0.260176 0.00498155 0.101938 0.0736125 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 692 742 1.29887e-11 -3.05972 -0.0937068 0.0612327 2.47802e-13 2.01617e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 742 743 5.09702 0.125646 -0.260634 0.00497849 0.102028 0.0734875 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 693 743 1.301e-11 -3.05972 -0.0937068 0.0612327 2.48246e-13 2.01172e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 743 744 5.10148 0.12549 -0.261091 0.0049754 0.102118 0.0733624 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 694 744 1.30136e-11 -3.05972 -0.0937068 0.0612327 2.48246e-13 2.01172e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 744 745 5.10594 0.125333 -0.261547 0.00497228 0.102208 0.0732372 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 695 745 1.30242e-11 -3.05972 -0.0937068 0.0612327 2.4869e-13 2.00728e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 745 746 5.11038 0.125175 -0.262003 0.00496915 0.102297 0.0731118 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 696 746 1.30349e-11 -3.05972 -0.0937068 0.0612327 2.4869e-13 2.00728e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 746 747 5.11482 0.125016 -0.262459 0.00496599 0.102386 0.0729864 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 697 747 1.30527e-11 -3.05972 -0.0937068 0.0612327 2.49134e-13 2.00284e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 747 748 5.11925 0.124855 -0.262914 0.00496281 0.102476 0.0728609 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 698 748 1.30616e-11 -3.05972 -0.0937068 0.0612327 2.49134e-13 1.9984e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 748 749 5.12367 0.124693 -0.263369 0.0049596 0.102565 0.0727352 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 699 749 1.30722e-11 -3.05972 -0.0937068 0.0612327 2.49578e-13 1.99396e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 749 750 5.12809 0.124531 -0.263824 0.00495638 0.102654 0.0726094 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 700 750 1.30824e-11 -3.05972 -0.0937068 0.0612327 2.49578e-13 1.99396e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 750 751 5.1325 0.124367 -0.264278 0.00495313 0.102742 0.0724835 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 701 751 1.30926e-11 -3.05972 -0.0937068 0.0612327 2.50022e-13 1.98952e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 751 752 5.1369 0.124202 -0.264732 0.00494986 0.102831 0.0723576 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 702 752 1.31024e-11 -3.05972 -0.0937068 0.0612327 2.50022e-13 1.98508e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 752 753 5.14129 0.124036 -0.265185 0.00494657 0.10292 0.0722314 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 703 753 1.31166e-11 -3.05972 -0.0937068 0.0612327 2.50466e-13 1.98508e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 753 754 5.14567 0.123869 -0.265638 0.00494325 0.103008 0.0721052 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 704 754 1.31308e-11 -3.05972 -0.0937068 0.0612327 2.50466e-13 1.98064e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 754 755 5.15005 0.123701 -0.266091 0.00493991 0.103096 0.0719789 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 705 755 1.31415e-11 -3.05972 -0.0937068 0.0612327 2.5091e-13 1.9762e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 755 756 5.15442 0.123531 -0.266543 0.00493655 0.103184 0.0718525 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 706 756 1.31521e-11 -3.05972 -0.0937068 0.0612327 2.51354e-13 1.9762e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 756 757 5.15878 0.123361 -0.266995 0.00493317 0.103272 0.0717259 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 707 757 1.31628e-11 -3.05972 -0.0937068 0.0612327 2.51354e-13 1.97176e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 757 758 5.16313 0.123189 -0.267446 0.00492976 0.103359 0.0715993 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 708 758 1.31699e-11 -3.05972 -0.0937068 0.0612327 2.51799e-13 1.96732e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 758 759 5.16748 0.123016 -0.267897 0.00492634 0.103447 0.0714725 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 709 759 1.31841e-11 -3.05972 -0.0937068 0.0612327 2.51799e-13 1.96732e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 759 760 5.17181 0.122843 -0.268348 0.00492289 0.103534 0.0713457 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 710 760 1.31912e-11 -3.05972 -0.0937068 0.0612327 2.52243e-13 1.96287e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 760 761 5.17614 0.122668 -0.268798 0.00491941 0.103622 0.0712187 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 711 761 1.32045e-11 -3.05972 -0.0937068 0.0612327 2.52243e-13 1.95843e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 761 762 5.18047 0.122492 -0.269247 0.00491592 0.103709 0.0710916 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 712 762 1.32161e-11 -3.05972 -0.0937068 0.0612327 2.52687e-13 1.95399e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 762 763 5.18478 0.122315 -0.269696 0.0049124 0.103796 0.0709644 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 713 763 1.32268e-11 -3.05972 -0.0937068 0.0612327 2.52687e-13 1.95399e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 763 764 5.18909 0.122137 -0.270145 0.00490886 0.103882 0.0708371 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 714 764 1.32392e-11 -3.05972 -0.0937068 0.0612327 2.53131e-13 1.94955e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 764 765 5.19339 0.121957 -0.270594 0.0049053 0.103969 0.0707097 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 715 765 1.32481e-11 -3.05972 -0.0937068 0.0612327 2.53575e-13 1.94511e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 765 766 5.19768 0.121777 -0.271041 0.00490172 0.104055 0.0705821 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 716 766 1.32623e-11 -3.05972 -0.0937068 0.0612327 2.53575e-13 1.94511e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 766 767 5.20196 0.121595 -0.271489 0.00489812 0.104142 0.0704545 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 717 767 1.32729e-11 -3.05972 -0.0937068 0.0612327 2.54019e-13 1.94067e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 767 768 5.20624 0.121413 -0.271936 0.00489449 0.104228 0.0703268 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 718 768 1.328e-11 -3.05972 -0.0937068 0.0612327 2.54019e-13 1.93623e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 768 769 5.2105 0.121229 -0.272382 0.00489084 0.104314 0.0701989 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 719 769 1.32907e-11 -3.05972 -0.0937068 0.0612327 2.54019e-13 1.93623e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 769 770 5.21476 0.121044 -0.272828 0.00488717 0.1044 0.070071 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 720 770 1.33014e-11 -3.05972 -0.0937068 0.0612327 2.54463e-13 1.93179e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 770 771 5.21902 0.120859 -0.273274 0.00488347 0.104485 0.0699429 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 721 771 1.33085e-11 -3.05972 -0.0937068 0.0612327 2.54907e-13 1.92735e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 771 772 5.22326 0.120672 -0.273719 0.00487976 0.104571 0.0698148 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 722 772 1.33245e-11 -3.05972 -0.0937068 0.0612327 2.54907e-13 1.92291e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 772 773 5.2275 0.120484 -0.274164 0.00487602 0.104656 0.0696865 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 723 773 1.33369e-11 -3.05972 -0.0937068 0.0612327 2.55351e-13 1.92291e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 773 774 5.23173 0.120294 -0.274608 0.00487226 0.104741 0.0695581 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 724 774 1.33467e-11 -3.05972 -0.0937068 0.0612327 2.55351e-13 1.91847e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 774 775 5.23595 0.120104 -0.275052 0.00486848 0.104826 0.0694296 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 725 775 1.33569e-11 -3.05972 -0.0937068 0.0612327 2.55795e-13 1.91402e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 775 776 5.24016 0.119913 -0.275495 0.00486467 0.104911 0.069301 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 726 776 1.3368e-11 -3.05972 -0.0937068 0.0612327 2.55795e-13 1.91402e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 776 777 5.24436 0.11972 -0.275938 0.00486085 0.104996 0.0691723 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 727 777 1.33813e-11 -3.05972 -0.0937068 0.0612327 2.56239e-13 1.90958e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 777 778 5.24856 0.119527 -0.276381 0.004857 0.105081 0.0690435 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 728 778 1.33866e-11 -3.05972 -0.0937068 0.0612327 2.56684e-13 1.90514e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 778 779 5.25275 0.119332 -0.276823 0.00485313 0.105165 0.0689146 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 729 779 1.33973e-11 -3.05972 -0.0937068 0.0612327 2.56684e-13 1.9007e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 779 780 5.25693 0.119137 -0.277264 0.00484924 0.105249 0.0687856 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 730 780 1.3415e-11 -3.05972 -0.0937068 0.0612327 2.56684e-13 1.9007e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 780 781 5.2611 0.11894 -0.277705 0.00484533 0.105333 0.0686565 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 731 781 1.34222e-11 -3.05972 -0.0937068 0.0612327 2.57128e-13 1.89626e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 781 782 5.26527 0.118742 -0.278145 0.00484139 0.105417 0.0685273 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 732 782 1.34293e-11 -3.05972 -0.0937068 0.0612327 2.57572e-13 1.89182e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 782 783 5.26943 0.118543 -0.278585 0.00483744 0.105501 0.0683979 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 733 783 1.34364e-11 -3.05972 -0.0937068 0.0612327 2.57572e-13 1.89182e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 783 784 5.27358 0.118344 -0.279025 0.00483346 0.105585 0.0682685 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 734 784 1.34524e-11 -3.05972 -0.0937068 0.0612327 2.57572e-13 1.88738e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 784 785 5.27772 0.118142 -0.279464 0.00482946 0.105668 0.068139 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 735 785 1.34595e-11 -3.05972 -0.0937068 0.0612327 2.58016e-13 1.88294e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 785 786 5.28185 0.11794 -0.279902 0.00482543 0.105751 0.0680093 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 736 786 1.34737e-11 -3.05972 -0.0937068 0.0612327 2.5846e-13 1.88294e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 786 787 5.28598 0.117737 -0.28034 0.00482139 0.105835 0.0678796 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 737 787 1.34839e-11 -3.05972 -0.0937068 0.0612327 2.5846e-13 1.8785e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 787 788 5.2901 0.117533 -0.280778 0.00481733 0.105918 0.0677497 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 738 788 1.3495e-11 -3.05972 -0.0937068 0.0612327 2.58904e-13 1.87406e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 788 789 5.29421 0.117328 -0.281215 0.00481324 0.106 0.0676198 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 739 789 1.35048e-11 -3.05972 -0.0937068 0.0612327 2.58904e-13 1.86962e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 789 790 5.29831 0.117121 -0.281651 0.00480913 0.106083 0.0674897 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 740 790 1.35145e-11 -3.05972 -0.0937068 0.0612327 2.59348e-13 1.86962e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 790 791 5.3024 0.116914 -0.282087 0.004805 0.106166 0.0673596 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 741 791 1.35252e-11 -3.05972 -0.0937068 0.0612327 2.59348e-13 1.86517e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 791 792 5.30649 0.116705 -0.282523 0.00480085 0.106248 0.0672293 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 742 792 1.35394e-11 -3.05972 -0.0937068 0.0612327 2.59792e-13 1.86073e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 792 793 5.31057 0.116496 -0.282958 0.00479667 0.10633 0.0670989 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 743 793 1.35465e-11 -3.05972 -0.0937068 0.0612327 2.59792e-13 1.85629e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 793 794 5.31464 0.116285 -0.283392 0.00479248 0.106412 0.0669685 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 744 794 1.35572e-11 -3.05972 -0.0937068 0.0612327 2.60236e-13 1.85629e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 794 795 5.3187 0.116073 -0.283826 0.00478826 0.106494 0.0668379 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 745 795 1.35678e-11 -3.05972 -0.0937068 0.0612327 2.60236e-13 1.85185e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 795 796 5.32276 0.115861 -0.28426 0.00478402 0.106576 0.0667072 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 746 796 1.3582e-11 -3.05972 -0.0937068 0.0612327 2.6068e-13 1.84741e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 796 797 5.3268 0.115647 -0.284693 0.00477976 0.106657 0.0665765 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 747 797 1.35856e-11 -3.05972 -0.0937068 0.0612327 2.6068e-13 1.84741e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 797 798 5.33084 0.115432 -0.285125 0.00477548 0.106739 0.0664456 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 748 798 1.3598e-11 -3.05972 -0.0937068 0.0612327 2.61124e-13 1.84297e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 798 799 5.33487 0.115216 -0.285557 0.00477118 0.10682 0.0663146 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 749 799 1.36096e-11 -3.05972 -0.0937068 0.0612327 2.61124e-13 1.83853e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 799 800 5.3389 0.114999 -0.285988 0.00476686 0.106901 0.0661835 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 750 800 1.3619e-11 -3.05972 -0.0937068 0.0612327 2.61569e-13 1.83853e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 800 801 5.34291 0.114781 -0.286419 0.00476251 0.106982 0.0660523 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 751 801 1.36309e-11 -3.05972 -0.0937068 0.0612327 2.61569e-13 1.83409e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 801 802 5.34692 0.114562 -0.286849 0.00475815 0.107063 0.0659211 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 752 802 1.36389e-11 -3.05972 -0.0937068 0.0612327 2.62013e-13 1.82965e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 802 803 5.35091 0.114341 -0.287279 0.00475376 0.107143 0.0657897 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 753 803 1.36495e-11 -3.05972 -0.0937068 0.0612327 2.62013e-13 1.82521e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 803 804 5.3549 0.11412 -0.287708 0.00474935 0.107224 0.0656582 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 754 804 1.36531e-11 -3.05972 -0.0937068 0.0612327 2.62457e-13 1.82521e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 804 805 5.35889 0.113898 -0.288137 0.00474492 0.107304 0.0655266 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 755 805 1.36673e-11 -3.05972 -0.0937068 0.0612327 2.62457e-13 1.82077e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 805 806 5.36286 0.113675 -0.288565 0.00474047 0.107384 0.0653949 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 756 806 1.36779e-11 -3.05972 -0.0937068 0.0612327 2.62901e-13 1.81632e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 806 807 5.36683 0.11345 -0.288992 0.00473599 0.107464 0.0652631 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 757 807 1.36957e-11 -3.05972 -0.0937068 0.0612327 2.62901e-13 1.81188e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 807 808 5.37079 0.113225 -0.289419 0.0047315 0.107544 0.0651313 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 758 808 1.36957e-11 -3.05972 -0.0937068 0.0612327 2.63345e-13 1.81188e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 808 809 5.37474 0.112998 -0.289846 0.00472698 0.107623 0.0649993 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 759 809 1.37081e-11 -3.05972 -0.0937068 0.0612327 2.63345e-13 1.80744e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 809 810 5.37868 0.112771 -0.290272 0.00472245 0.107703 0.0648672 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 760 810 1.37206e-11 -3.05972 -0.0937068 0.0612327 2.63789e-13 1.803e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 810 811 5.38261 0.112542 -0.290697 0.00471789 0.107782 0.064735 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 761 811 1.37277e-11 -3.05972 -0.0937068 0.0612327 2.63789e-13 1.803e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 811 812 5.38654 0.112313 -0.291122 0.00471331 0.107861 0.0646027 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 762 812 1.37401e-11 -3.05972 -0.0937068 0.0612327 2.64233e-13 1.79856e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 812 813 5.39046 0.112082 -0.291546 0.00470871 0.10794 0.0644704 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 763 813 1.37503e-11 -3.05972 -0.0937068 0.0612327 2.64233e-13 1.79412e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 813 814 5.39437 0.11185 -0.291969 0.00470409 0.108019 0.0643379 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 764 814 1.37605e-11 -3.05972 -0.0937068 0.0612327 2.64677e-13 1.78968e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 814 815 5.39827 0.111618 -0.292393 0.00469945 0.108098 0.0642053 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 765 815 1.37721e-11 -3.05972 -0.0937068 0.0612327 2.64677e-13 1.78968e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 815 816 5.40216 0.111384 -0.292815 0.00469479 0.108176 0.0640726 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 766 816 1.37828e-11 -3.05972 -0.0937068 0.0612327 2.65121e-13 1.78524e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 816 817 5.40605 0.111149 -0.293237 0.00469011 0.108255 0.0639398 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 767 817 1.37881e-11 -3.05972 -0.0937068 0.0612327 2.65121e-13 1.7808e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 817 818 5.40993 0.110913 -0.293658 0.0046854 0.108333 0.063807 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 768 818 1.37987e-11 -3.05972 -0.0937068 0.0612327 2.65565e-13 1.77636e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 818 819 5.41379 0.110676 -0.294079 0.00468068 0.108411 0.063674 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 769 819 1.38094e-11 -3.05972 -0.0937068 0.0612327 2.65565e-13 1.77636e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 819 820 5.41766 0.110439 -0.294499 0.00467593 0.108489 0.0635409 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 770 820 1.38165e-11 -3.05972 -0.0937068 0.0612327 2.66009e-13 1.77192e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 820 821 5.42151 0.1102 -0.294919 0.00467116 0.108566 0.0634078 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 771 821 1.38307e-11 -3.05972 -0.0937068 0.0612327 2.66009e-13 1.76748e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 821 822 5.42535 0.10996 -0.295338 0.00466638 0.108644 0.0632745 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 772 822 1.38414e-11 -3.05972 -0.0937068 0.0612327 2.66454e-13 1.76748e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 822 823 5.42919 0.109719 -0.295756 0.00466157 0.108721 0.0631412 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 773 823 1.38485e-11 -3.05972 -0.0937068 0.0612327 2.66454e-13 1.76303e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 823 824 5.43302 0.109477 -0.296174 0.00465674 0.108798 0.0630077 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 774 824 1.38574e-11 -3.05972 -0.0937068 0.0612327 2.66898e-13 1.75859e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 824 825 5.43684 0.109234 -0.296591 0.00465189 0.108875 0.0628741 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 775 825 1.38682e-11 -3.05972 -0.0937068 0.0612327 2.66898e-13 1.75415e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 825 826 5.44065 0.10899 -0.297008 0.00464702 0.108952 0.0627405 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 776 826 1.38778e-11 -3.05972 -0.0937068 0.0612327 2.67342e-13 1.75415e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 826 827 5.44446 0.108745 -0.297424 0.00464213 0.109029 0.0626068 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 777 827 1.38858e-11 -3.05972 -0.0937068 0.0612327 2.67342e-13 1.74971e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 827 828 5.44825 0.108499 -0.297839 0.00463721 0.109105 0.0624729 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 778 828 1.38982e-11 -3.05972 -0.0937068 0.0612327 2.67342e-13 1.74527e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 828 829 5.45204 0.108252 -0.298254 0.00463228 0.109182 0.062339 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 779 829 1.39018e-11 -3.05972 -0.0937068 0.0612327 2.67786e-13 1.74083e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 829 830 5.45582 0.108004 -0.298668 0.00462733 0.109258 0.062205 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 780 830 1.3916e-11 -3.05972 -0.0937068 0.0612327 2.6823e-13 1.74083e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 830 831 5.45959 0.107754 -0.299082 0.00462236 0.109334 0.0620708 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 781 831 1.39266e-11 -3.05972 -0.0937068 0.0612327 2.6823e-13 1.73639e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 831 832 5.46336 0.107504 -0.299495 0.00461736 0.10941 0.0619366 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 782 832 1.39408e-11 -3.05972 -0.0937068 0.0612327 2.68674e-13 1.73195e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 832 833 5.46711 0.107253 -0.299907 0.00461235 0.109486 0.0618023 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 783 833 1.3948e-11 -3.05972 -0.0937068 0.0612327 2.68674e-13 1.73195e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 833 834 5.47086 0.107001 -0.300319 0.00460731 0.109561 0.0616679 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 784 834 1.39551e-11 -3.05972 -0.0937068 0.0612327 2.69118e-13 1.72751e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 834 835 5.4746 0.106748 -0.30073 0.00460226 0.109637 0.0615334 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 785 835 1.39639e-11 -3.05972 -0.0937068 0.0612327 2.69118e-13 1.72307e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 835 836 5.47833 0.106494 -0.301141 0.00459718 0.109712 0.0613988 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 786 836 1.39737e-11 -3.05972 -0.0937068 0.0612327 2.69118e-13 1.71863e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 836 837 5.48205 0.106239 -0.301551 0.00459208 0.109787 0.0612641 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 787 837 1.3983e-11 -3.05972 -0.0937068 0.0612327 2.69562e-13 1.71418e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 837 838 5.48576 0.105982 -0.30196 0.00458697 0.109862 0.0611293 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 788 838 1.39928e-11 -3.05972 -0.0937068 0.0612327 2.69562e-13 1.71418e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 838 839 5.48947 0.105725 -0.302369 0.00458183 0.109937 0.0609944 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 789 839 1.40021e-11 -3.05972 -0.0937068 0.0612327 2.70006e-13 1.70974e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 839 840 5.49317 0.105467 -0.302777 0.00457667 0.110011 0.0608594 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 790 840 1.40137e-11 -3.05972 -0.0937068 0.0612327 2.70006e-13 1.7053e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 840 841 5.49686 0.105208 -0.303184 0.0045715 0.110086 0.0607244 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 791 841 1.40226e-11 -3.05972 -0.0937068 0.0612327 2.7045e-13 1.70086e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 841 842 5.50054 0.104948 -0.303591 0.0045663 0.11016 0.0605892 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 792 842 1.40297e-11 -3.05972 -0.0937068 0.0612327 2.7045e-13 1.70086e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 842 843 5.50421 0.104687 -0.303997 0.00456108 0.110234 0.060454 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 793 843 1.40439e-11 -3.05972 -0.0937068 0.0612327 2.70894e-13 1.69642e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 843 844 5.50788 0.104424 -0.304403 0.00455584 0.110308 0.0603186 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 794 844 1.40474e-11 -3.05972 -0.0937068 0.0612327 2.70894e-13 1.69198e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 844 845 5.51153 0.104161 -0.304807 0.00455059 0.110382 0.0601832 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 795 845 1.40581e-11 -3.05972 -0.0937068 0.0612327 2.71339e-13 1.69198e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 845 846 5.51518 0.103897 -0.305212 0.00454531 0.110455 0.0600476 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 796 846 1.40652e-11 -3.05972 -0.0937068 0.0612327 2.71339e-13 1.68754e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 846 847 5.51882 0.103632 -0.305615 0.00454001 0.110529 0.059912 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 797 847 1.40741e-11 -3.05972 -0.0937068 0.0612327 2.71783e-13 1.6831e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 847 848 5.52245 0.103366 -0.306018 0.00453469 0.110602 0.0597763 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 798 848 1.40883e-11 -3.05972 -0.0937068 0.0612327 2.71783e-13 1.67866e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 848 849 5.52607 0.103099 -0.30642 0.00452935 0.110675 0.0596405 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 799 849 1.40954e-11 -3.05972 -0.0937068 0.0612327 2.71783e-13 1.67422e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 849 850 5.52969 0.102831 -0.306822 0.004524 0.110748 0.0595046 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 800 850 1.41045e-11 -3.05972 -0.0937068 0.0612327 2.72227e-13 1.67422e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 850 851 5.5333 0.102562 -0.307223 0.00451862 0.11082 0.0593686 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 801 851 1.41132e-11 -3.05972 -0.0937068 0.0612327 2.72227e-13 1.66978e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 851 852 5.53689 0.102292 -0.307623 0.00451322 0.110893 0.0592325 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 802 852 1.4122e-11 -3.05972 -0.0937068 0.0612327 2.72671e-13 1.66533e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 852 853 5.54048 0.102021 -0.308023 0.0045078 0.110965 0.0590964 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 803 853 1.41345e-11 -3.05972 -0.0937068 0.0612327 2.72671e-13 1.66089e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 853 854 5.54407 0.101749 -0.308422 0.00450237 0.111038 0.0589601 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 804 854 1.41362e-11 -3.05972 -0.0937068 0.0612327 2.73115e-13 1.66089e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 854 855 5.54764 0.101476 -0.30882 0.00449691 0.11111 0.0588237 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 805 855 1.4154e-11 -3.05972 -0.0937068 0.0612327 2.73115e-13 1.65645e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 855 856 5.55121 0.101202 -0.309217 0.00449143 0.111182 0.0586873 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 806 856 1.41611e-11 -3.05972 -0.0937068 0.0612327 2.73559e-13 1.65201e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 856 857 5.55476 0.100927 -0.309614 0.00448593 0.111253 0.0585508 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 807 857 1.41682e-11 -3.05972 -0.0937068 0.0612327 2.73559e-13 1.65201e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 857 858 5.55831 0.100651 -0.310011 0.00448042 0.111325 0.0584141 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 808 858 1.41789e-11 -3.05972 -0.0937068 0.0612327 2.74003e-13 1.64757e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 858 859 5.56185 0.100374 -0.310406 0.00447488 0.111396 0.0582774 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 809 859 1.41895e-11 -3.05972 -0.0937068 0.0612327 2.74003e-13 1.64313e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 859 860 5.56538 0.100096 -0.310801 0.00446933 0.111468 0.0581406 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 810 860 1.41966e-11 -3.05972 -0.0937068 0.0612327 2.74447e-13 1.63869e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 860 861 5.56891 0.0998174 -0.311195 0.00446375 0.111539 0.0580037 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 811 861 1.42064e-11 -3.05972 -0.0937068 0.0612327 2.74447e-13 1.63425e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 861 862 5.57242 0.0995376 -0.311589 0.00445816 0.11161 0.0578668 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 812 862 1.42131e-11 -3.05972 -0.0937068 0.0612327 2.74447e-13 1.63425e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 862 863 5.57593 0.0992569 -0.311982 0.00445254 0.11168 0.0577297 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 813 863 1.4222e-11 -3.05972 -0.0937068 0.0612327 2.74891e-13 1.62981e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 863 864 5.57943 0.0989752 -0.312374 0.00444691 0.111751 0.0575925 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 814 864 1.42304e-11 -3.05972 -0.0937068 0.0612327 2.74891e-13 1.62537e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 864 865 5.58292 0.0986925 -0.312765 0.00444125 0.111821 0.0574553 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 815 865 1.42393e-11 -3.05972 -0.0937068 0.0612327 2.75335e-13 1.62093e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 865 866 5.5864 0.0984089 -0.313156 0.00443558 0.111892 0.057318 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 816 866 1.42464e-11 -3.05972 -0.0937068 0.0612327 2.75335e-13 1.62093e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 866 867 5.58987 0.0981244 -0.313546 0.00442989 0.111962 0.0571805 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 817 867 1.4257e-11 -3.05972 -0.0937068 0.0612327 2.75779e-13 1.61648e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 867 868 5.59334 0.0978388 -0.313935 0.00442418 0.112032 0.057043 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 818 868 1.42677e-11 -3.05972 -0.0937068 0.0612327 2.75779e-13 1.61204e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 868 869 5.59679 0.0975524 -0.314324 0.00441845 0.112101 0.0569054 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 819 869 1.42784e-11 -3.05972 -0.0937068 0.0612327 2.76223e-13 1.6076e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 869 870 5.60024 0.0972649 -0.314712 0.0044127 0.112171 0.0567677 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 820 870 1.42855e-11 -3.05972 -0.0937068 0.0612327 2.76223e-13 1.6076e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 870 871 5.60368 0.0969766 -0.315099 0.00440693 0.11224 0.05663 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 821 871 1.42926e-11 -3.05972 -0.0937068 0.0612327 2.76223e-13 1.60316e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 871 872 5.60711 0.0966873 -0.315486 0.00440114 0.11231 0.0564921 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 822 872 1.42979e-11 -3.05972 -0.0937068 0.0612327 2.76668e-13 1.59872e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 872 873 5.61054 0.096397 -0.315872 0.00439533 0.112379 0.0563542 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 823 873 1.43068e-11 -3.05972 -0.0937068 0.0612327 2.76668e-13 1.59428e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 873 874 5.61395 0.0961058 -0.316257 0.0043895 0.112448 0.0562161 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 824 874 1.43192e-11 -3.05972 -0.0937068 0.0612327 2.77112e-13 1.59428e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 874 875 5.61736 0.0958136 -0.316641 0.00438366 0.112516 0.056078 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 825 875 1.43275e-11 -3.05972 -0.0937068 0.0612327 2.77112e-13 1.58984e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 875 876 5.62075 0.0955205 -0.317025 0.00437779 0.112585 0.0559398 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 826 876 1.43361e-11 -3.05972 -0.0937068 0.0612327 2.77556e-13 1.5854e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 876 877 5.62414 0.0952265 -0.317408 0.00437191 0.112653 0.0558015 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 827 877 1.43441e-11 -3.05972 -0.0937068 0.0612327 2.77556e-13 1.58096e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 877 878 5.62752 0.0949315 -0.31779 0.004366 0.112721 0.0556632 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 828 878 1.43547e-11 -3.05972 -0.0937068 0.0612327 2.77556e-13 1.57652e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 878 879 5.6309 0.0946356 -0.318172 0.00436008 0.112789 0.0555247 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 829 879 1.43636e-11 -3.05972 -0.0937068 0.0612327 2.78e-13 1.57652e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 879 880 5.63426 0.0943388 -0.318553 0.00435414 0.112857 0.0553861 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 830 880 1.43707e-11 -3.05972 -0.0937068 0.0612327 2.78e-13 1.57208e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 880 881 5.63762 0.094041 -0.318933 0.00434818 0.112925 0.0552475 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 831 881 1.43778e-11 -3.05972 -0.0937068 0.0612327 2.78444e-13 1.56763e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 881 882 5.64096 0.0937423 -0.319312 0.0043422 0.112993 0.0551088 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 832 882 1.43885e-11 -3.05972 -0.0937068 0.0612327 2.78444e-13 1.56319e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 882 883 5.6443 0.0934427 -0.319691 0.0043362 0.11306 0.05497 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 833 883 1.43991e-11 -3.05972 -0.0937068 0.0612327 2.78888e-13 1.56319e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 883 884 5.64763 0.0931421 -0.320069 0.00433019 0.113127 0.0548311 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 834 884 1.44063e-11 -3.05972 -0.0937068 0.0612327 2.78888e-13 1.55875e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 884 885 5.65095 0.0928407 -0.320446 0.00432415 0.113194 0.0546921 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 835 885 1.44151e-11 -3.05972 -0.0937068 0.0612327 2.78888e-13 1.55431e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 885 886 5.65427 0.0925383 -0.320822 0.0043181 0.113261 0.0545531 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 836 886 1.44222e-11 -3.05972 -0.0937068 0.0612327 2.79332e-13 1.54987e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 886 887 5.65757 0.0922349 -0.321198 0.00431202 0.113328 0.054414 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 837 887 1.44298e-11 -3.05972 -0.0937068 0.0612327 2.79332e-13 1.54987e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 887 888 5.66087 0.0919307 -0.321573 0.00430593 0.113394 0.0542747 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 838 888 1.44382e-11 -3.05972 -0.0937068 0.0612327 2.79776e-13 1.54543e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 888 889 5.66415 0.0916255 -0.321947 0.00429982 0.113461 0.0541354 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 839 889 1.44471e-11 -3.05972 -0.0937068 0.0612327 2.79776e-13 1.54099e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 889 890 5.66743 0.0913195 -0.32232 0.00429369 0.113527 0.053996 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 840 890 1.44524e-11 -3.05972 -0.0937068 0.0612327 2.8022e-13 1.53655e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 890 891 5.6707 0.0910125 -0.322693 0.00428755 0.113593 0.0538566 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 841 891 1.44631e-11 -3.05972 -0.0937068 0.0612327 2.8022e-13 1.53211e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 891 892 5.67397 0.0907046 -0.323065 0.00428138 0.113659 0.053717 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 842 892 1.44773e-11 -3.05972 -0.0937068 0.0612327 2.80664e-13 1.53211e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 892 893 5.67722 0.0903958 -0.323436 0.0042752 0.113724 0.0535774 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 843 893 1.44773e-11 -3.05972 -0.0937068 0.0612327 2.80664e-13 1.52767e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 893 894 5.68047 0.090086 -0.323807 0.00426899 0.11379 0.0534377 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 844 894 1.44915e-11 -3.05972 -0.0937068 0.0612327 2.80664e-13 1.52323e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 894 895 5.6837 0.0897754 -0.324176 0.00426277 0.113855 0.0532979 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 845 895 1.44951e-11 -3.05972 -0.0937068 0.0612327 2.81108e-13 1.51879e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 895 896 5.68693 0.0894639 -0.324545 0.00425653 0.11392 0.053158 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 846 896 1.45022e-11 -3.05972 -0.0937068 0.0612327 2.81108e-13 1.51879e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 896 897 5.69015 0.0891515 -0.324913 0.00425027 0.113985 0.053018 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 847 897 1.45164e-11 -3.05972 -0.0937068 0.0612327 2.81553e-13 1.51434e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 897 898 5.69336 0.0888381 -0.325281 0.004244 0.11405 0.052878 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 848 898 1.45199e-11 -3.05972 -0.0937068 0.0612327 2.81553e-13 1.5099e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 898 899 5.69656 0.0885239 -0.325647 0.0042377 0.114115 0.0527379 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 849 899 1.45297e-11 -3.05972 -0.0937068 0.0612327 2.81553e-13 1.50546e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 899 900 5.69976 0.0882088 -0.326013 0.00423139 0.114179 0.0525977 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 850 900 1.45371e-11 -3.05972 -0.0937068 0.0612327 2.81997e-13 1.50546e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 900 901 5.70294 0.0878927 -0.326378 0.00422506 0.114243 0.0524574 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 851 901 1.45466e-11 -3.05972 -0.0937068 0.0612327 2.81997e-13 1.50102e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 901 902 5.70612 0.0875758 -0.326742 0.00421871 0.114308 0.052317 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 852 902 1.45537e-11 -3.05972 -0.0937068 0.0612327 2.82441e-13 1.49658e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 902 903 5.70929 0.087258 -0.327106 0.00421234 0.114372 0.0521766 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 853 903 1.4559e-11 -3.05972 -0.0937068 0.0612327 2.82441e-13 1.49214e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 903 904 5.71245 0.0869393 -0.327469 0.00420596 0.114435 0.052036 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 854 904 1.45732e-11 -3.05972 -0.0937068 0.0612327 2.82441e-13 1.4877e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 904 905 5.7156 0.0866197 -0.32783 0.00419956 0.114499 0.0518954 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 855 905 1.45768e-11 -3.05972 -0.0937068 0.0612327 2.82885e-13 1.4877e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 905 906 5.71874 0.0862993 -0.328192 0.00419313 0.114562 0.0517547 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 856 906 1.45874e-11 -3.05972 -0.0937068 0.0612327 2.82885e-13 1.48326e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 906 907 5.72188 0.0859779 -0.328552 0.0041867 0.114626 0.051614 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 857 907 1.45945e-11 -3.05972 -0.0937068 0.0612327 2.83329e-13 1.47882e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 907 908 5.725 0.0856557 -0.328912 0.00418024 0.114689 0.0514731 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 858 908 1.46017e-11 -3.05972 -0.0937068 0.0612327 2.83329e-13 1.47438e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 908 909 5.72812 0.0853326 -0.32927 0.00417376 0.114752 0.0513322 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 859 909 1.46088e-11 -3.05972 -0.0937068 0.0612327 2.83773e-13 1.46994e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 909 910 5.73123 0.0850086 -0.329628 0.00416727 0.114814 0.0511912 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 860 910 1.46194e-11 -3.05972 -0.0937068 0.0612327 2.83773e-13 1.46994e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 910 911 5.73433 0.0846837 -0.329986 0.00416076 0.114877 0.0510501 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 861 911 1.46247e-11 -3.05972 -0.0937068 0.0612327 2.83773e-13 1.46549e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 911 912 5.73742 0.0843579 -0.330342 0.00415423 0.114939 0.0509089 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 862 912 1.46332e-11 -3.05972 -0.0937068 0.0612327 2.84217e-13 1.46105e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 912 913 5.7405 0.0840313 -0.330698 0.00414769 0.115002 0.0507677 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 863 913 1.46412e-11 -3.05972 -0.0937068 0.0612327 2.84217e-13 1.45661e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 913 914 5.74357 0.0837038 -0.331052 0.00414112 0.115064 0.0506264 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 864 914 1.46478e-11 -3.05972 -0.0937068 0.0612327 2.84661e-13 1.45661e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 914 915 5.74664 0.0833755 -0.331406 0.00413454 0.115126 0.050485 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 865 915 1.46567e-11 -3.05972 -0.0937068 0.0612327 2.84661e-13 1.45217e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 915 916 5.7497 0.0830463 -0.33176 0.00412794 0.115187 0.0503435 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 866 916 1.4662e-11 -3.05972 -0.0937068 0.0612327 2.84661e-13 1.44773e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 916 917 5.75274 0.0827162 -0.332112 0.00412133 0.115249 0.050202 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 867 917 1.46727e-11 -3.05972 -0.0937068 0.0612327 2.85105e-13 1.44329e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 917 918 5.75578 0.0823852 -0.332464 0.00411469 0.11531 0.0500603 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 868 918 1.46763e-11 -3.05972 -0.0937068 0.0612327 2.85105e-13 1.43885e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 918 919 5.75881 0.0820534 -0.332814 0.00410804 0.115371 0.0499186 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 869 919 1.46869e-11 -3.05972 -0.0937068 0.0612327 2.85549e-13 1.43885e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 919 920 5.76184 0.0817208 -0.333164 0.00410137 0.115432 0.0497768 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 870 920 1.46976e-11 -3.05972 -0.0937068 0.0612327 2.85549e-13 1.43441e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 920 921 5.76485 0.0813873 -0.333513 0.00409469 0.115493 0.049635 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 871 921 1.47047e-11 -3.05972 -0.0937068 0.0612327 2.85993e-13 1.42997e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 921 922 5.76785 0.0810529 -0.333862 0.00408798 0.115554 0.0494931 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 872 922 1.47153e-11 -3.05972 -0.0937068 0.0612327 2.85993e-13 1.42553e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 922 923 5.77085 0.0807177 -0.334209 0.00408126 0.115614 0.049351 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 873 923 1.47171e-11 -3.05972 -0.0937068 0.0612327 2.85993e-13 1.42109e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 923 924 5.77384 0.0803816 -0.334556 0.00407452 0.115675 0.049209 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 874 924 1.47242e-11 -3.05972 -0.0937068 0.0612327 2.85993e-13 1.42109e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 924 925 5.77682 0.0800447 -0.334902 0.00406777 0.115735 0.0490668 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 875 925 1.47331e-11 -3.05972 -0.0937068 0.0612327 2.86438e-13 1.41664e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 925 926 5.77979 0.0797069 -0.335247 0.004061 0.115795 0.0489246 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 876 926 1.47411e-11 -3.05972 -0.0937068 0.0612327 2.86438e-13 1.4122e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 926 927 5.78275 0.0793683 -0.335591 0.00405421 0.115855 0.0487822 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 877 927 1.47455e-11 -3.05972 -0.0937068 0.0612327 2.86882e-13 1.40776e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 927 928 5.7857 0.0790288 -0.335934 0.0040474 0.115914 0.0486399 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 878 928 1.47562e-11 -3.05972 -0.0937068 0.0612327 2.86882e-13 1.40776e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 928 929 5.78865 0.0786885 -0.336277 0.00404057 0.115974 0.0484974 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 879 929 1.47615e-11 -3.05972 -0.0937068 0.0612327 2.86882e-13 1.40332e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 929 930 5.79158 0.0783474 -0.336619 0.00403373 0.116033 0.0483549 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 880 930 1.47722e-11 -3.05972 -0.0937068 0.0612327 2.87326e-13 1.39888e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 930 931 5.79451 0.0780054 -0.336959 0.00402688 0.116092 0.0482122 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 881 931 1.47757e-11 -3.05972 -0.0937068 0.0612327 2.87326e-13 1.39444e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 931 932 5.79743 0.0776626 -0.337299 0.00402 0.116151 0.0480696 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 882 932 1.47828e-11 -3.05972 -0.0937068 0.0612327 2.8777e-13 1.39e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 932 933 5.80033 0.077319 -0.337639 0.00401311 0.11621 0.0479268 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 883 933 1.47899e-11 -3.05972 -0.0937068 0.0612327 2.8777e-13 1.39e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 933 934 5.80324 0.0769745 -0.337977 0.0040062 0.116268 0.047784 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 884 934 1.48006e-11 -3.05972 -0.0937068 0.0612327 2.8777e-13 1.38556e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 934 935 5.80613 0.0766292 -0.338314 0.00399927 0.116327 0.0476411 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 885 935 1.48077e-11 -3.05972 -0.0937068 0.0612327 2.88214e-13 1.38112e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 935 936 5.80901 0.0762831 -0.338651 0.00399233 0.116385 0.0474981 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 886 936 1.48166e-11 -3.05972 -0.0937068 0.0612327 2.88214e-13 1.37668e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 936 937 5.81189 0.0759361 -0.338987 0.00398537 0.116443 0.047355 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 887 937 1.48224e-11 -3.05972 -0.0937068 0.0612327 2.88658e-13 1.37224e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 937 938 5.81475 0.0755884 -0.339322 0.0039784 0.116501 0.0472119 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 888 938 1.4829e-11 -3.05972 -0.0937068 0.0612327 2.88658e-13 1.37224e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 938 939 5.81761 0.0752398 -0.339656 0.0039714 0.116559 0.0470687 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 889 939 1.48361e-11 -3.05972 -0.0937068 0.0612327 2.88658e-13 1.36779e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 939 940 5.82046 0.0748904 -0.339989 0.0039644 0.116616 0.0469254 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 890 940 1.4845e-11 -3.05972 -0.0937068 0.0612327 2.89102e-13 1.36335e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 940 941 5.8233 0.0745402 -0.340322 0.00395737 0.116674 0.0467821 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 891 941 1.48468e-11 -3.05972 -0.0937068 0.0612327 2.89102e-13 1.35891e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 941 942 5.82613 0.0741892 -0.340653 0.00395033 0.116731 0.0466387 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 892 942 1.4861e-11 -3.05972 -0.0937068 0.0612327 2.89546e-13 1.35447e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 942 943 5.82895 0.0738373 -0.340984 0.00394327 0.116788 0.0464952 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 893 943 1.48646e-11 -3.05972 -0.0937068 0.0612327 2.89546e-13 1.35447e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 943 944 5.83176 0.0734847 -0.341314 0.00393619 0.116845 0.0463516 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 894 944 1.48681e-11 -3.05972 -0.0937068 0.0612327 2.89546e-13 1.35003e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 944 945 5.83457 0.0731312 -0.341643 0.0039291 0.116901 0.046208 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 895 945 1.48823e-11 -3.05972 -0.0937068 0.0612327 2.8999e-13 1.34559e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 945 946 5.83736 0.0727769 -0.341971 0.00392199 0.116958 0.0460643 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 896 946 1.4893e-11 -3.05972 -0.0937068 0.0612327 2.8999e-13 1.34115e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 946 947 5.84015 0.0724219 -0.342298 0.00391487 0.117014 0.0459205 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 897 947 1.48894e-11 -3.05972 -0.0937068 0.0612327 2.8999e-13 1.33671e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 947 948 5.84293 0.072066 -0.342624 0.00390773 0.11707 0.0457767 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 898 948 1.49019e-11 -3.05972 -0.0937068 0.0612327 2.90434e-13 1.33671e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 948 949 5.8457 0.0717094 -0.34295 0.00390057 0.117126 0.0456328 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 899 949 1.49081e-11 -3.05972 -0.0937068 0.0612327 2.90434e-13 1.33227e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 949 950 5.84846 0.0713519 -0.343274 0.0038934 0.117182 0.0454888 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 900 950 1.49153e-11 -3.05972 -0.0937068 0.0612327 2.90434e-13 1.32783e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 950 951 5.85121 0.0709937 -0.343598 0.00388621 0.117238 0.0453447 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 901 951 1.49223e-11 -3.05972 -0.0937068 0.0612327 2.90878e-13 1.32339e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 951 952 5.85396 0.0706346 -0.343921 0.00387901 0.117293 0.0452006 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 902 952 1.49285e-11 -3.05972 -0.0937068 0.0612327 2.90878e-13 1.31894e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 952 953 5.85669 0.0702748 -0.344243 0.00387178 0.117348 0.0450564 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 903 953 1.49338e-11 -3.05972 -0.0937068 0.0612327 2.91323e-13 1.31894e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 953 954 5.85942 0.0699142 -0.344564 0.00386455 0.117403 0.0449121 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 904 954 1.49427e-11 -3.05972 -0.0937068 0.0612327 2.91323e-13 1.3145e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 954 955 5.86213 0.0695528 -0.344884 0.00385729 0.117458 0.0447678 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 905 955 1.49498e-11 -3.05972 -0.0937068 0.0612327 2.91323e-13 1.31006e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 955 956 5.86484 0.0691906 -0.345203 0.00385002 0.117513 0.0446234 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 906 956 1.49569e-11 -3.05972 -0.0937068 0.0612327 2.91767e-13 1.30562e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 956 957 5.86754 0.0688276 -0.345522 0.00384274 0.117567 0.0444789 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 907 957 1.49605e-11 -3.05972 -0.0937068 0.0612327 2.91767e-13 1.30118e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 957 958 5.87023 0.0684638 -0.345839 0.00383544 0.117622 0.0443344 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 908 958 1.49747e-11 -3.05972 -0.0937068 0.0612327 2.91767e-13 1.30118e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 958 959 5.87291 0.0680993 -0.346156 0.00382812 0.117676 0.0441898 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 909 959 1.49711e-11 -3.05972 -0.0937068 0.0612327 2.92211e-13 1.29674e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 959 960 5.87559 0.067734 -0.346472 0.00382079 0.11773 0.0440451 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 910 960 1.49853e-11 -3.05972 -0.0937068 0.0612327 2.92211e-13 1.2923e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 960 961 5.87825 0.0673679 -0.346786 0.00381344 0.117784 0.0439004 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 911 961 1.49907e-11 -3.05972 -0.0937068 0.0612327 2.92211e-13 1.28786e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 961 962 5.88091 0.0670011 -0.3471 0.00380608 0.117838 0.0437556 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 912 962 1.49982e-11 -3.05972 -0.0937068 0.0612327 2.92655e-13 1.28342e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 962 963 5.88355 0.0666335 -0.347413 0.0037987 0.117891 0.0436107 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 913 963 1.50053e-11 -3.05972 -0.0937068 0.0612327 2.92655e-13 1.28342e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 963 964 5.88619 0.0662651 -0.347726 0.0037913 0.117944 0.0434658 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 914 964 1.50102e-11 -3.05972 -0.0937068 0.0612327 2.92655e-13 1.27898e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 964 965 5.88882 0.065896 -0.348037 0.00378389 0.117997 0.0433207 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 915 965 1.50155e-11 -3.05972 -0.0937068 0.0612327 2.93099e-13 1.27454e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 965 966 5.89144 0.0655261 -0.348347 0.00377647 0.11805 0.0431757 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 916 966 1.50244e-11 -3.05972 -0.0937068 0.0612327 2.93099e-13 1.2701e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 966 967 5.89405 0.0651554 -0.348657 0.00376902 0.118103 0.0430305 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 917 967 1.5028e-11 -3.05972 -0.0937068 0.0612327 2.93099e-13 1.26565e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 967 968 5.89665 0.064784 -0.348965 0.00376157 0.118156 0.0428853 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 918 968 1.50351e-11 -3.05972 -0.0937068 0.0612327 2.93543e-13 1.26565e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 968 969 5.89925 0.0644118 -0.349273 0.00375409 0.118208 0.04274 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 919 969 1.50457e-11 -3.05972 -0.0937068 0.0612327 2.93543e-13 1.26121e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 969 970 5.90183 0.0640389 -0.349579 0.00374661 0.11826 0.0425947 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 920 970 1.50493e-11 -3.05972 -0.0937068 0.0612327 2.93543e-13 1.25677e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 970 971 5.90441 0.0636652 -0.349885 0.0037391 0.118312 0.0424493 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 921 971 1.50564e-11 -3.05972 -0.0937068 0.0612327 2.93987e-13 1.25233e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 971 972 5.90698 0.0632908 -0.35019 0.00373159 0.118364 0.0423038 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 922 972 1.50635e-11 -3.05972 -0.0937068 0.0612327 2.93987e-13 1.24789e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 972 973 5.90953 0.0629157 -0.350494 0.00372405 0.118416 0.0421583 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 923 973 1.50742e-11 -3.05972 -0.0937068 0.0612327 2.93987e-13 1.24345e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 973 974 5.91208 0.0625397 -0.350797 0.0037165 0.118468 0.0420127 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 924 974 1.50777e-11 -3.05972 -0.0937068 0.0612327 2.94431e-13 1.24345e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 974 975 5.91462 0.0621631 -0.351099 0.00370894 0.118519 0.041867 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 925 975 1.50835e-11 -3.05972 -0.0937068 0.0612327 2.94431e-13 1.23901e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 975 976 5.91716 0.0617857 -0.3514 0.00370136 0.11857 0.0417213 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 926 976 1.5091e-11 -3.05972 -0.0937068 0.0612327 2.94875e-13 1.23457e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 976 977 5.91968 0.0614076 -0.3517 0.00369377 0.118621 0.0415755 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 927 977 1.50973e-11 -3.05972 -0.0937068 0.0612327 2.94875e-13 1.23013e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 977 978 5.92219 0.0610287 -0.352 0.00368616 0.118672 0.0414296 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 928 978 1.51008e-11 -3.05972 -0.0937068 0.0612327 2.94875e-13 1.22569e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 978 979 5.9247 0.0606491 -0.352298 0.00367854 0.118723 0.0412837 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 929 979 1.51097e-11 -3.05972 -0.0937068 0.0612327 2.94875e-13 1.22569e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 979 980 5.92719 0.0602688 -0.352596 0.0036709 0.118773 0.0411377 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 930 980 1.51132e-11 -3.05972 -0.0937068 0.0612327 2.95319e-13 1.22125e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 980 981 5.92968 0.0598878 -0.352892 0.00366324 0.118823 0.0409916 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 931 981 1.51275e-11 -3.05972 -0.0937068 0.0612327 2.95319e-13 1.2168e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 981 982 5.93216 0.059506 -0.353188 0.00365558 0.118873 0.0408455 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 932 982 1.51346e-11 -3.05972 -0.0937068 0.0612327 2.95763e-13 1.21236e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 982 983 5.93463 0.0591235 -0.353482 0.00364789 0.118923 0.0406994 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 933 983 1.51381e-11 -3.05972 -0.0937068 0.0612327 2.95763e-13 1.20792e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 983 984 5.93709 0.0587403 -0.353776 0.0036402 0.118973 0.0405531 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 934 984 1.51346e-11 -3.05972 -0.0937068 0.0612327 2.95763e-13 1.20348e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 984 985 5.93954 0.0583563 -0.354069 0.00363248 0.119023 0.0404068 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 935 985 1.5147e-11 -3.05972 -0.0937068 0.0612327 2.96208e-13 1.20348e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 985 986 5.94198 0.0579717 -0.354361 0.00362476 0.119072 0.0402604 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 936 986 1.51541e-11 -3.05972 -0.0937068 0.0612327 2.96208e-13 1.19904e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 986 987 5.94442 0.0575863 -0.354652 0.00361702 0.119121 0.040114 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 937 987 1.51585e-11 -3.05972 -0.0937068 0.0612327 2.96208e-13 1.1946e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 987 988 5.94684 0.0572002 -0.354942 0.00360926 0.11917 0.0399675 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 938 988 1.51656e-11 -3.05972 -0.0937068 0.0612327 2.96652e-13 1.19016e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 988 989 5.94926 0.0568135 -0.355231 0.00360149 0.119219 0.039821 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 939 989 1.51719e-11 -3.05972 -0.0937068 0.0612327 2.96652e-13 1.18572e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 989 990 5.95166 0.056426 -0.355519 0.00359371 0.119268 0.0396744 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 940 990 1.51736e-11 -3.05972 -0.0937068 0.0612327 2.96652e-13 1.18572e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 990 991 5.95406 0.0560378 -0.355806 0.00358591 0.119316 0.0395277 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 941 991 1.51879e-11 -3.05972 -0.0937068 0.0612327 2.97096e-13 1.18128e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 991 992 5.95645 0.0556489 -0.356092 0.0035781 0.119364 0.039381 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 942 992 1.51843e-11 -3.05972 -0.0937068 0.0612327 2.97096e-13 1.17684e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 992 993 5.95883 0.0552593 -0.356377 0.00357027 0.119413 0.0392342 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 943 993 1.52021e-11 -3.05972 -0.0937068 0.0612327 2.97096e-13 1.1724e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 993 994 5.9612 0.054869 -0.356662 0.00356243 0.119461 0.0390873 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 944 994 1.52092e-11 -3.05972 -0.0937068 0.0612327 2.97096e-13 1.16795e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 994 995 5.96357 0.054478 -0.356945 0.00355457 0.119508 0.0389404 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 945 995 1.52056e-11 -3.05972 -0.0937068 0.0612327 2.9754e-13 1.16795e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 995 996 5.96592 0.0540863 -0.357227 0.0035467 0.119556 0.0387934 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 946 996 1.52127e-11 -3.05972 -0.0937068 0.0612327 2.9754e-13 1.16351e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 996 997 5.96826 0.0536939 -0.357509 0.00353882 0.119603 0.0386464 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 947 997 1.52216e-11 -3.05972 -0.0937068 0.0612327 2.9754e-13 1.15907e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 997 998 5.9706 0.0533009 -0.357789 0.00353092 0.119651 0.0384993 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 948 998 1.52234e-11 -3.05972 -0.0937068 0.0612327 2.97984e-13 1.15463e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 998 999 5.97292 0.0529071 -0.358068 0.00352301 0.119698 0.0383521 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 949 999 1.52323e-11 -3.05972 -0.0937068 0.0612327 2.97984e-13 1.15019e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 999 1000 5.97524 0.0525127 -0.358347 0.00351508 0.119744 0.0382049 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 950 1000 1.52375e-11 -3.05972 -0.0937068 0.0612327 2.97984e-13 1.14575e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1000 1001 5.97755 0.0521176 -0.358624 0.00350714 0.119791 0.0380576 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 951 1001 1.5242e-11 -3.05972 -0.0937068 0.0612327 2.98428e-13 1.14575e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1001 1002 5.97985 0.0517218 -0.358901 0.00349919 0.119838 0.0379103 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 952 1002 1.525e-11 -3.05972 -0.0937068 0.0612327 2.98428e-13 1.14131e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1002 1003 5.98214 0.0513253 -0.359177 0.00349122 0.119884 0.0377629 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 953 1003 1.52571e-11 -3.05972 -0.0937068 0.0612327 2.98428e-13 1.13687e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1003 1004 5.98442 0.0509282 -0.359451 0.00348324 0.11993 0.0376155 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 954 1004 1.52625e-11 -3.05972 -0.0937068 0.0612327 2.98872e-13 1.13243e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1004 1005 5.9867 0.0505303 -0.359725 0.00347525 0.119976 0.037468 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 955 1005 1.5266e-11 -3.05972 -0.0937068 0.0612327 2.98872e-13 1.12799e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1005 1006 5.98896 0.0501319 -0.359998 0.00346724 0.120022 0.0373204 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 956 1006 1.5266e-11 -3.05972 -0.0937068 0.0612327 2.98872e-13 1.12799e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1006 1007 5.99121 0.0497327 -0.360269 0.00345922 0.120067 0.0371728 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 957 1007 1.52767e-11 -3.05972 -0.0937068 0.0612327 3.12195e-13 1.1724e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1007 1008 5.99346 0.0493329 -0.36054 0.00345118 0.120113 0.0370251 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 958 1008 1.52802e-11 -3.05972 -0.0937068 0.0612327 3.12639e-13 1.16795e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1008 1009 5.9957 0.0489324 -0.36081 0.00344313 0.120158 0.0368774 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 959 1009 1.52944e-11 -3.05972 -0.0937068 0.0612327 3.12639e-13 1.16351e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1009 1010 5.99793 0.0485313 -0.361078 0.00343507 0.120203 0.0367296 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 960 1010 1.52927e-11 -3.05972 -0.0937068 0.0612327 3.12639e-13 1.15907e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1010 1011 6.00014 0.0481295 -0.361346 0.00342699 0.120248 0.0365817 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 961 1011 1.52998e-11 -3.05972 -0.0937068 0.0612327 3.13083e-13 1.15463e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1011 1012 6.00235 0.0477271 -0.361613 0.00341891 0.120293 0.0364338 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 962 1012 1.53064e-11 -3.05972 -0.0937068 0.0612327 3.13083e-13 1.15463e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1012 1013 6.00455 0.047324 -0.361879 0.0034108 0.120337 0.0362859 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 963 1013 1.53126e-11 -3.05972 -0.0937068 0.0612327 3.13527e-13 1.15019e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1013 1014 6.00675 0.0469202 -0.362144 0.00340269 0.120382 0.0361378 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 964 1014 1.53175e-11 -3.05972 -0.0937068 0.0612327 3.13527e-13 1.14575e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1014 1015 6.00893 0.0465158 -0.362407 0.00339456 0.120426 0.0359898 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 965 1015 1.53246e-11 -3.05972 -0.0937068 0.0612327 3.13527e-13 1.14131e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1015 1016 6.0111 0.0461108 -0.36267 0.00338642 0.12047 0.0358416 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 966 1016 1.533e-11 -3.05972 -0.0937068 0.0612327 3.13527e-13 1.13687e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1016 1017 6.01327 0.0457051 -0.362932 0.00337826 0.120514 0.0356935 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 967 1017 1.533e-11 -3.05972 -0.0937068 0.0612327 3.13971e-13 1.13243e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1017 1018 6.01542 0.0452988 -0.363193 0.00337009 0.120557 0.0355452 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 968 1018 1.53406e-11 -3.05972 -0.0937068 0.0612327 3.13971e-13 1.12799e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1018 1019 6.01757 0.0448918 -0.363453 0.00336191 0.120601 0.0353969 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 969 1019 1.46656e-11 -3.05972 -0.0937068 0.0612327 2.87326e-13 1.03029e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1019 1020 6.01971 0.0444842 -0.363711 0.00335372 0.120644 0.0352486 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 970 1020 1.46656e-11 -3.05972 -0.0937068 0.0612327 2.8777e-13 1.02585e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1020 1021 6.02184 0.044076 -0.363969 0.00334551 0.120687 0.0351002 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 971 1021 1.46692e-11 -3.05972 -0.0937068 0.0612327 2.8777e-13 1.02141e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1021 1022 6.02396 0.0436671 -0.364226 0.00333729 0.12073 0.0349517 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 972 1022 1.46798e-11 -3.05972 -0.0937068 0.0612327 2.8777e-13 1.02141e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1022 1023 6.02607 0.0432577 -0.364482 0.00332906 0.120773 0.0348032 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 973 1023 1.46798e-11 -3.05972 -0.0937068 0.0612327 2.8777e-13 1.01696e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1023 1024 6.02817 0.0428475 -0.364737 0.00332081 0.120815 0.0346546 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 974 1024 1.46896e-11 -3.05972 -0.0937068 0.0612327 2.8777e-13 1.01252e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1024 1025 6.03026 0.0424368 -0.364991 0.00331256 0.120857 0.034506 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 975 1025 1.46936e-11 -3.05972 -0.0937068 0.0612327 2.88214e-13 1.00808e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1025 1026 6.03234 0.0420255 -0.365244 0.00330429 0.1209 0.0343574 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 976 1026 1.46994e-11 -3.05972 -0.0937068 0.0612327 2.88214e-13 1.00364e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1026 1027 6.03442 0.0416135 -0.365495 0.003296 0.120942 0.0342086 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 977 1027 1.47047e-11 -3.05972 -0.0937068 0.0612327 2.88214e-13 1.00364e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1027 1028 6.03648 0.0412009 -0.365746 0.00328771 0.120983 0.0340599 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 978 1028 1.47118e-11 -3.05972 -0.0937068 0.0612327 2.88658e-13 9.99201e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1028 1029 6.03854 0.0407877 -0.365996 0.0032794 0.121025 0.033911 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 979 1029 1.47118e-11 -3.05972 -0.0937068 0.0612327 2.88658e-13 9.9476e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1029 1030 6.04059 0.0403739 -0.366245 0.00327108 0.121066 0.0337621 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 980 1030 1.47224e-11 -3.05972 -0.0937068 0.0612327 2.88658e-13 9.90319e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1030 1031 6.04263 0.0399595 -0.366492 0.00326274 0.121108 0.0336132 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 981 1031 1.4726e-11 -3.05972 -0.0937068 0.0612327 2.88658e-13 9.85878e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1031 1032 6.04466 0.0395444 -0.366739 0.0032544 0.121149 0.0334642 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 982 1032 1.4726e-11 -3.05972 -0.0937068 0.0612327 2.89102e-13 9.85878e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1032 1033 6.04668 0.0391288 -0.366985 0.00324604 0.12119 0.0333152 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 983 1033 1.47296e-11 -3.05972 -0.0937068 0.0612327 2.89102e-13 9.81437e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1033 1034 6.04869 0.0387126 -0.36723 0.00323767 0.12123 0.0331661 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 984 1034 1.47438e-11 -3.05972 -0.0937068 0.0612327 2.89102e-13 9.76996e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1034 1035 6.05069 0.0382957 -0.367473 0.00322929 0.121271 0.033017 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 985 1035 1.4742e-11 -3.05972 -0.0937068 0.0612327 2.89546e-13 9.72555e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1035 1036 6.05268 0.0378783 -0.367716 0.00322089 0.121311 0.0328678 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 986 1036 1.47473e-11 -3.05972 -0.0937068 0.0612327 2.89546e-13 9.68114e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1036 1037 6.05467 0.0374603 -0.367958 0.00321249 0.121351 0.0327185 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 987 1037 1.47526e-11 -3.05972 -0.0937068 0.0612327 2.89546e-13 9.68114e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1037 1038 6.05664 0.0370417 -0.368198 0.00320407 0.121391 0.0325692 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 988 1038 1.47566e-11 -3.05972 -0.0937068 0.0612327 2.89546e-13 9.63674e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1038 1039 6.05861 0.0366225 -0.368438 0.00319564 0.121431 0.0324199 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 989 1039 1.47633e-11 -3.05972 -0.0937068 0.0612327 2.8999e-13 9.59233e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1039 1040 6.06056 0.0362027 -0.368676 0.0031872 0.121471 0.0322705 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 990 1040 1.47686e-11 -3.05972 -0.0937068 0.0612327 2.8999e-13 9.54792e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1040 1041 6.06251 0.0357824 -0.368914 0.00317874 0.12151 0.032121 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 991 1041 1.47651e-11 -3.05972 -0.0937068 0.0612327 2.8999e-13 9.50351e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1041 1042 6.06445 0.0353614 -0.369151 0.00317027 0.121549 0.0319716 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 992 1042 1.47793e-11 -3.05972 -0.0937068 0.0612327 2.90434e-13 9.50351e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1042 1043 6.06638 0.0349399 -0.369386 0.0031618 0.121588 0.031822 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 993 1043 1.47793e-11 -3.05972 -0.0937068 0.0612327 2.90434e-13 9.4591e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1043 1044 6.0683 0.0345178 -0.36962 0.00315331 0.121627 0.0316724 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 994 1044 1.47757e-11 -3.05972 -0.0937068 0.0612327 2.90434e-13 9.41469e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1044 1045 6.07021 0.0340951 -0.369854 0.00314481 0.121666 0.0315228 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 995 1045 1.47864e-11 -3.05972 -0.0937068 0.0612327 2.90434e-13 9.37028e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1045 1046 6.07211 0.0336719 -0.370086 0.00313629 0.121704 0.0313731 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 996 1046 1.47971e-11 -3.05972 -0.0937068 0.0612327 2.90434e-13 9.32587e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1046 1047 6.074 0.0332481 -0.370318 0.00312777 0.121743 0.0312234 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 997 1047 1.47971e-11 -3.05972 -0.0937068 0.0612327 2.90878e-13 9.32587e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1047 1048 6.07589 0.0328237 -0.370548 0.00311923 0.121781 0.0310736 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 998 1048 1.48059e-11 -3.05972 -0.0937068 0.0612327 2.90878e-13 9.28146e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1048 1049 6.07776 0.0323988 -0.370777 0.00311068 0.121819 0.0309237 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 999 1049 1.48086e-11 -3.05972 -0.0937068 0.0612327 2.90878e-13 9.23706e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1049 1050 6.07963 0.0319733 -0.371005 0.00310212 0.121857 0.0307739 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1000 1050 1.48133e-11 -3.05972 -0.0937068 0.0612327 2.90878e-13 9.19265e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1050 1051 6.08148 0.0315472 -0.371233 0.00309355 0.121894 0.0306239 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1001 1051 1.48184e-11 -3.05972 -0.0937068 0.0612327 2.91323e-13 9.14824e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1051 1052 6.08333 0.0311206 -0.371459 0.00308497 0.121932 0.030474 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1002 1052 1.48201e-11 -3.05972 -0.0937068 0.0612327 2.91323e-13 9.14824e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1052 1053 6.08517 0.0306934 -0.371684 0.00307638 0.121969 0.0303239 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1003 1053 1.4829e-11 -3.05972 -0.0937068 0.0612327 2.91323e-13 9.10383e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1053 1054 6.087 0.0302657 -0.371908 0.00306777 0.122006 0.0301739 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1004 1054 1.48326e-11 -3.05972 -0.0937068 0.0612327 2.91323e-13 9.05942e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1054 1055 6.08882 0.0298375 -0.372131 0.00305916 0.122043 0.0300238 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1005 1055 1.48397e-11 -3.05972 -0.0937068 0.0612327 2.91767e-13 9.01501e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1055 1056 6.09063 0.0294087 -0.372353 0.00305053 0.122079 0.0298736 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1006 1056 1.48397e-11 -3.05972 -0.0937068 0.0612327 2.91767e-13 8.9706e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1056 1057 6.09243 0.0289793 -0.372574 0.00304189 0.122116 0.0297234 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1007 1057 1.4829e-11 -3.05972 -0.0937068 0.0612327 2.78444e-13 8.52651e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1057 1058 6.09422 0.0285494 -0.372793 0.00303325 0.122152 0.0295731 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1008 1058 1.48326e-11 -3.05972 -0.0937068 0.0612327 2.78444e-13 8.4821e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1058 1059 6.09601 0.028119 -0.373012 0.00302459 0.122188 0.0294228 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1009 1059 1.48397e-11 -3.05972 -0.0937068 0.0612327 2.78444e-13 8.4821e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1059 1060 6.09778 0.027688 -0.37323 0.00301592 0.122224 0.0292725 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1010 1060 1.48468e-11 -3.05972 -0.0937068 0.0612327 2.78444e-13 8.43769e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1060 1061 6.09955 0.0272565 -0.373447 0.00300723 0.12226 0.0291221 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1011 1061 1.48539e-11 -3.05972 -0.0937068 0.0612327 2.78888e-13 8.39329e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1061 1062 6.1013 0.0268245 -0.373662 0.00299854 0.122296 0.0289717 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1012 1062 1.48548e-11 -3.05972 -0.0937068 0.0612327 2.78888e-13 8.34888e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1062 1063 6.10305 0.026392 -0.373877 0.00298984 0.122331 0.0288212 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1013 1063 1.48588e-11 -3.05972 -0.0937068 0.0612327 2.78888e-13 8.34888e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1063 1064 6.10479 0.0259589 -0.37409 0.00298112 0.122366 0.0286707 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1014 1064 1.48628e-11 -3.05972 -0.0937068 0.0612327 2.78888e-13 8.30447e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1064 1065 6.10651 0.0255253 -0.374303 0.0029724 0.122401 0.0285201 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1015 1065 1.48699e-11 -3.05972 -0.0937068 0.0612327 2.78888e-13 8.26006e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1065 1066 6.10823 0.0250912 -0.374514 0.00296366 0.122436 0.0283695 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1016 1066 1.48717e-11 -3.05972 -0.0937068 0.0612327 2.79332e-13 8.21565e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1066 1067 6.10994 0.0246566 -0.374724 0.00295492 0.122471 0.0282188 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1017 1067 1.48823e-11 -3.05972 -0.0937068 0.0612327 2.79332e-13 8.21565e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1067 1068 6.11165 0.0242214 -0.374934 0.00294616 0.122505 0.0280681 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1018 1068 1.48788e-11 -3.05972 -0.0937068 0.0612327 2.79332e-13 8.17124e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1068 1069 6.11334 0.0237858 -0.375142 0.0029374 0.122539 0.0279174 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1019 1069 1.55858e-11 -3.05972 -0.0937068 0.0612327 3.06866e-13 8.92619e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1069 1070 6.11502 0.0233496 -0.375349 0.00292862 0.122573 0.0277666 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1020 1070 1.55964e-11 -3.05972 -0.0937068 0.0612327 3.06866e-13 8.88178e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1070 1071 6.11669 0.0229129 -0.375555 0.00291983 0.122607 0.0276158 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1021 1071 1.56e-11 -3.05972 -0.0937068 0.0612327 3.0731e-13 8.83738e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1071 1072 6.11836 0.0224758 -0.37576 0.00291104 0.122641 0.0274649 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1022 1072 1.56035e-11 -3.05972 -0.0937068 0.0612327 3.0731e-13 8.79297e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1072 1073 6.12001 0.0220381 -0.375964 0.00290223 0.122675 0.027314 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1023 1073 1.56053e-11 -3.05972 -0.0937068 0.0612327 3.0731e-13 8.74856e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1073 1074 6.12166 0.0215999 -0.376167 0.00289341 0.122708 0.027163 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1024 1074 1.56088e-11 -3.05972 -0.0937068 0.0612327 3.0731e-13 8.74856e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1074 1075 6.1233 0.0211613 -0.376369 0.00288458 0.122741 0.027012 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1025 1075 1.56135e-11 -3.05972 -0.0937068 0.0612327 3.0731e-13 8.70415e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1075 1076 6.12492 0.0207221 -0.376569 0.00287574 0.122774 0.026861 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1026 1076 1.56177e-11 -3.05972 -0.0937068 0.0612327 3.0731e-13 8.65974e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1076 1077 6.12654 0.0202825 -0.376769 0.0028669 0.122807 0.0267099 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1027 1077 1.56213e-11 -3.05972 -0.0937068 0.0612327 3.07754e-13 8.61533e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1077 1078 6.12815 0.0198423 -0.376967 0.00285804 0.12284 0.0265588 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1028 1078 1.56248e-11 -3.05972 -0.0937068 0.0612327 3.07754e-13 8.57092e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1078 1079 6.12975 0.0194017 -0.377165 0.00284917 0.122872 0.0264076 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1029 1079 1.56319e-11 -3.05972 -0.0937068 0.0612327 3.07754e-13 8.52651e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1079 1080 6.13134 0.0189606 -0.377361 0.00284029 0.122904 0.0262564 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1030 1080 1.56355e-11 -3.05972 -0.0937068 0.0612327 3.08198e-13 8.52651e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1080 1081 6.13292 0.018519 -0.377556 0.0028314 0.122936 0.0261052 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1031 1081 1.56426e-11 -3.05972 -0.0937068 0.0612327 3.08198e-13 8.4821e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1081 1082 6.1345 0.0180769 -0.377751 0.00282251 0.122968 0.0259539 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1032 1082 1.5639e-11 -3.05972 -0.0937068 0.0612327 3.08198e-13 8.43769e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1082 1083 6.13606 0.0176344 -0.377944 0.0028136 0.123 0.0258025 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1033 1083 1.56462e-11 -3.05972 -0.0937068 0.0612327 3.08198e-13 8.39329e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1083 1084 6.13761 0.0171914 -0.378136 0.00280468 0.123031 0.0256512 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1034 1084 1.56497e-11 -3.05972 -0.0937068 0.0612327 3.08198e-13 8.34888e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1084 1085 6.13916 0.0167479 -0.378327 0.00279576 0.123063 0.0254998 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1035 1085 1.5655e-11 -3.05972 -0.0937068 0.0612327 3.08642e-13 8.30447e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1085 1086 6.14069 0.016304 -0.378517 0.00278682 0.123094 0.0253483 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1036 1086 1.56586e-11 -3.05972 -0.0937068 0.0612327 3.08642e-13 8.26006e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1086 1087 6.14222 0.0158596 -0.378705 0.00277788 0.123125 0.0251968 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1037 1087 1.56617e-11 -3.05972 -0.0937068 0.0612327 3.08642e-13 8.26006e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1087 1088 6.14374 0.0154147 -0.378893 0.00276892 0.123155 0.0250453 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1038 1088 1.56661e-11 -3.05972 -0.0937068 0.0612327 3.08642e-13 8.21565e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1088 1089 6.14525 0.0149694 -0.37908 0.00275996 0.123186 0.0248938 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1039 1089 1.56692e-11 -3.05972 -0.0937068 0.0612327 3.09086e-13 8.17124e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1089 1090 6.14674 0.0145236 -0.379265 0.00275098 0.123216 0.0247422 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1040 1090 1.56728e-11 -3.05972 -0.0937068 0.0612327 3.09086e-13 8.12683e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1090 1091 6.14823 0.0140774 -0.37945 0.002742 0.123247 0.0245905 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1041 1091 1.56817e-11 -3.05972 -0.0937068 0.0612327 3.09086e-13 8.08242e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1091 1092 6.14971 0.0136307 -0.379633 0.00273301 0.123277 0.0244388 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1042 1092 1.56781e-11 -3.05972 -0.0937068 0.0612327 3.09086e-13 8.03801e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1092 1093 6.15119 0.0131836 -0.379815 0.00272401 0.123307 0.0242871 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1043 1093 1.56852e-11 -3.05972 -0.0937068 0.0612327 3.09086e-13 7.99361e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1093 1094 6.15265 0.012736 -0.379996 0.002715 0.123336 0.0241354 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1044 1094 1.56923e-11 -3.05972 -0.0937068 0.0612327 3.0953e-13 7.99361e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1094 1095 6.1541 0.012288 -0.380176 0.00270598 0.123366 0.0239836 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1045 1095 1.56994e-11 -3.05972 -0.0937068 0.0612327 3.0953e-13 7.9492e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1095 1096 6.15554 0.0118395 -0.380355 0.00269695 0.123395 0.0238318 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1046 1096 1.56959e-11 -3.05972 -0.0937068 0.0612327 3.0953e-13 7.90479e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1096 1097 6.15698 0.0113906 -0.380533 0.00268791 0.123424 0.0236799 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1047 1097 1.56923e-11 -3.05972 -0.0937068 0.0612327 3.0953e-13 7.86038e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1097 1098 6.1584 0.0109413 -0.38071 0.00267887 0.123453 0.023528 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1048 1098 1.56994e-11 -3.05972 -0.0937068 0.0612327 3.09974e-13 7.81597e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1098 1099 6.15982 0.0104915 -0.380885 0.00266981 0.123482 0.0233761 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1049 1099 1.57048e-11 -3.05972 -0.0937068 0.0612327 3.09974e-13 7.77156e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1099 1100 6.16122 0.0100413 -0.38106 0.00266075 0.12351 0.0232241 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1050 1100 1.57097e-11 -3.05972 -0.0937068 0.0612327 3.09974e-13 7.72715e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1100 1101 6.16262 0.00959072 -0.381233 0.00265168 0.123538 0.0230721 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1051 1101 1.57137e-11 -3.05972 -0.0937068 0.0612327 3.09974e-13 7.72715e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1101 1102 6.16401 0.00913968 -0.381406 0.0026426 0.123567 0.02292 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1052 1102 1.57172e-11 -3.05972 -0.0937068 0.0612327 3.09974e-13 7.68274e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1102 1103 6.16539 0.00868822 -0.381577 0.00263351 0.123595 0.022768 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1053 1103 1.57208e-11 -3.05972 -0.0937068 0.0612327 3.10418e-13 7.63833e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1103 1104 6.16676 0.00823634 -0.381747 0.00262441 0.123622 0.0226158 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1054 1104 1.57243e-11 -3.05972 -0.0937068 0.0612327 3.10418e-13 7.59393e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1104 1105 6.16812 0.00778405 -0.381916 0.0026153 0.12365 0.0224637 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1055 1105 1.57208e-11 -3.05972 -0.0937068 0.0612327 3.10418e-13 7.54952e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1105 1106 6.16947 0.00733134 -0.382084 0.00260619 0.123677 0.0223115 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1056 1106 1.5735e-11 -3.05972 -0.0937068 0.0612327 3.10418e-13 7.50511e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1106 1107 6.17081 0.00687822 -0.382251 0.00259706 0.123705 0.0221593 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1057 1107 1.57314e-11 -3.05972 -0.0937068 0.0612327 3.10418e-13 7.4607e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1107 1108 6.17214 0.0064247 -0.382416 0.00258793 0.123732 0.022007 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1058 1108 1.57385e-11 -3.05972 -0.0937068 0.0612327 3.10862e-13 7.4607e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1108 1109 6.17347 0.00597077 -0.382581 0.00257879 0.123759 0.0218547 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1059 1109 1.57421e-11 -3.05972 -0.0937068 0.0612327 3.10862e-13 7.41629e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1109 1110 6.17478 0.00551644 -0.382744 0.00256964 0.123785 0.0217024 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1060 1110 1.57439e-11 -3.05972 -0.0937068 0.0612327 3.10862e-13 7.37188e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1110 1111 6.17609 0.00506171 -0.382907 0.00256049 0.123812 0.0215501 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1061 1111 1.57439e-11 -3.05972 -0.0937068 0.0612327 3.10862e-13 7.32747e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1111 1112 6.17738 0.00460659 -0.383068 0.00255132 0.123838 0.0213977 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1062 1112 1.57505e-11 -3.05972 -0.0937068 0.0612327 3.10862e-13 7.28306e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1112 1113 6.17867 0.00415107 -0.383228 0.00254215 0.123864 0.0212453 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1063 1113 1.57541e-11 -3.05972 -0.0937068 0.0612327 3.11307e-13 7.23865e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1113 1114 6.17994 0.00369516 -0.383387 0.00253297 0.12389 0.0210928 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1064 1114 1.57581e-11 -3.05972 -0.0937068 0.0612327 3.11307e-13 7.19425e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1114 1115 6.18121 0.00323886 -0.383545 0.00252378 0.123916 0.0209403 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1065 1115 1.57634e-11 -3.05972 -0.0937068 0.0612327 3.11307e-13 7.19425e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1115 1116 6.18247 0.00278218 -0.383702 0.00251459 0.123941 0.0207878 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1066 1116 1.57634e-11 -3.05972 -0.0937068 0.0612327 3.11307e-13 7.14984e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1116 1117 6.18372 0.00232512 -0.383857 0.00250538 0.123967 0.0206353 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1067 1117 1.57705e-11 -3.05972 -0.0937068 0.0612327 3.11751e-13 7.10543e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1117 1118 6.18496 0.00186767 -0.384012 0.00249617 0.123992 0.0204827 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1068 1118 1.5774e-11 -3.05972 -0.0937068 0.0612327 3.11751e-13 7.06102e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1118 1119 6.18619 0.00140985 -0.384165 0.00248695 0.124017 0.0203301 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1069 1119 1.5774e-11 -3.05972 -0.0937068 0.0612327 3.11751e-13 7.01661e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1119 1120 6.18741 0.000951654 -0.384318 0.00247772 0.124042 0.0201774 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1070 1120 1.5774e-11 -3.05972 -0.0937068 0.0612327 3.11751e-13 6.9722e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1120 1121 6.18862 0.000493086 -0.384469 0.00246849 0.124066 0.0200247 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1071 1121 1.57776e-11 -3.05972 -0.0937068 0.0612327 3.11751e-13 6.92779e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1121 1122 6.18983 3.41497e-05 -0.384619 0.00245925 0.124091 0.019872 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1072 1122 1.57847e-11 -3.05972 -0.0937068 0.0612327 3.11751e-13 6.92779e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1122 1123 6.19102 -0.000425153 -0.384768 0.00245 0.124115 0.0197193 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1073 1123 1.57865e-11 -3.05972 -0.0937068 0.0612327 3.12195e-13 6.88338e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1123 1124 6.1922 -0.000884819 -0.384915 0.00244074 0.124139 0.0195665 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1074 1124 1.57891e-11 -3.05972 -0.0937068 0.0612327 3.12195e-13 6.83897e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1124 1125 6.19338 -0.00134485 -0.385062 0.00243147 0.124163 0.0194137 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1075 1125 1.57912e-11 -3.05972 -0.0937068 0.0612327 3.12195e-13 6.79456e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1125 1126 6.19454 -0.00180523 -0.385208 0.0024222 0.124187 0.0192609 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1076 1126 1.57927e-11 -3.05972 -0.0937068 0.0612327 3.12195e-13 6.75016e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1126 1127 6.1957 -0.00226597 -0.385352 0.00241292 0.12421 0.019108 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1077 1127 1.57971e-11 -3.05972 -0.0937068 0.0612327 3.12195e-13 6.70575e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1127 1128 6.19685 -0.00272706 -0.385495 0.00240364 0.124233 0.0189552 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1078 1128 1.58025e-11 -3.05972 -0.0937068 0.0612327 3.12639e-13 6.66134e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1128 1129 6.19799 -0.0031885 -0.385637 0.00239434 0.124256 0.0188022 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1079 1129 1.5806e-11 -3.05972 -0.0937068 0.0612327 3.12639e-13 6.66134e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1129 1130 6.19911 -0.00365029 -0.385778 0.00238504 0.124279 0.0186493 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1080 1130 1.57989e-11 -3.05972 -0.0937068 0.0612327 3.12639e-13 6.61693e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1130 1131 6.20023 -0.00411242 -0.385918 0.00237573 0.124302 0.0184963 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1081 1131 1.58096e-11 -3.05972 -0.0937068 0.0612327 3.12639e-13 6.57252e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1131 1132 6.20134 -0.0045749 -0.386057 0.00236642 0.124325 0.0183433 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1082 1132 1.58096e-11 -3.05972 -0.0937068 0.0612327 3.12639e-13 6.52811e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1132 1133 6.20244 -0.00503771 -0.386195 0.0023571 0.124347 0.0181903 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1083 1133 1.58131e-11 -3.05972 -0.0937068 0.0612327 3.13083e-13 6.4837e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1133 1134 6.20353 -0.00550086 -0.386331 0.00234777 0.124369 0.0180372 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1084 1134 1.58202e-11 -3.05972 -0.0937068 0.0612327 3.13083e-13 6.43929e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1134 1135 6.20462 -0.00596434 -0.386467 0.00233843 0.124391 0.0178841 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1085 1135 1.58202e-11 -3.05972 -0.0937068 0.0612327 3.13083e-13 6.39488e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1135 1136 6.20569 -0.00642815 -0.386601 0.00232909 0.124413 0.017731 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1086 1136 1.58238e-11 -3.05972 -0.0937068 0.0612327 3.13083e-13 6.39488e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1136 1137 6.20675 -0.00689229 -0.386734 0.00231974 0.124435 0.0175779 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1087 1137 1.58251e-11 -3.05972 -0.0937068 0.0612327 3.13083e-13 6.35048e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1137 1138 6.20781 -0.00735675 -0.386866 0.00231039 0.124456 0.0174247 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1088 1138 1.58273e-11 -3.05972 -0.0937068 0.0612327 3.13083e-13 6.30607e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1138 1139 6.20885 -0.00782153 -0.386997 0.00230103 0.124477 0.0172715 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1089 1139 1.58291e-11 -3.05972 -0.0937068 0.0612327 3.13527e-13 6.26166e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1139 1140 6.20989 -0.00828664 -0.387126 0.00229166 0.124498 0.0171183 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1090 1140 1.58327e-11 -3.05972 -0.0937068 0.0612327 3.13527e-13 6.21725e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1140 1141 6.21091 -0.00875206 -0.387255 0.00228228 0.124519 0.016965 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1091 1141 1.58309e-11 -3.05972 -0.0937068 0.0612327 3.13527e-13 6.17284e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1141 1142 6.21193 -0.00921779 -0.387382 0.0022729 0.12454 0.0168117 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1092 1142 1.58344e-11 -3.05972 -0.0937068 0.0612327 3.13527e-13 6.12843e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1142 1143 6.21294 -0.00968383 -0.387508 0.00226351 0.12456 0.0166584 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1093 1143 1.58344e-11 -3.05972 -0.0937068 0.0612327 3.13527e-13 6.12843e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1143 1144 6.21393 -0.0101502 -0.387633 0.00225412 0.124581 0.0165051 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1094 1144 1.58451e-11 -3.05972 -0.0937068 0.0612327 3.13527e-13 6.08402e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1144 1145 6.21492 -0.0106168 -0.387757 0.00224472 0.124601 0.0163518 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1095 1145 1.58416e-11 -3.05972 -0.0937068 0.0612327 3.13971e-13 6.03961e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1145 1146 6.2159 -0.0110838 -0.38788 0.00223531 0.124621 0.0161984 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1096 1146 1.58451e-11 -3.05972 -0.0937068 0.0612327 3.13971e-13 5.9952e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1146 1147 6.21687 -0.0115511 -0.388002 0.0022259 0.124641 0.016045 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1097 1147 1.58558e-11 -3.05972 -0.0937068 0.0612327 3.13971e-13 5.9508e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1147 1148 6.21783 -0.0120186 -0.388122 0.00221648 0.12466 0.0158915 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1098 1148 1.5854e-11 -3.05972 -0.0937068 0.0612327 3.13971e-13 5.90639e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1148 1149 6.21879 -0.0124865 -0.388242 0.00220706 0.124679 0.0157381 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1099 1149 1.58566e-11 -3.05972 -0.0937068 0.0612327 3.13971e-13 5.86198e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1149 1150 6.21973 -0.0129546 -0.38836 0.00219762 0.124699 0.0155846 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1100 1150 1.58578e-11 -3.05972 -0.0937068 0.0612327 3.13971e-13 5.81757e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1150 1151 6.22066 -0.013423 -0.388477 0.00218819 0.124718 0.0154311 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1101 1151 1.58611e-11 -3.05972 -0.0937068 0.0612327 3.13971e-13 5.81757e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1151 1152 6.22158 -0.0138917 -0.388593 0.00217875 0.124736 0.0152776 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1102 1152 1.58629e-11 -3.05972 -0.0937068 0.0612327 3.14415e-13 5.77316e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1152 1153 6.2225 -0.0143607 -0.388708 0.0021693 0.124755 0.015124 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1103 1153 1.58664e-11 -3.05972 -0.0937068 0.0612327 3.14415e-13 5.72875e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1153 1154 6.2234 -0.01483 -0.388821 0.00215984 0.124773 0.0149705 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1104 1154 1.58664e-11 -3.05972 -0.0937068 0.0612327 3.14415e-13 5.68434e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1154 1155 6.2243 -0.0152996 -0.388934 0.00215038 0.124792 0.0148169 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1105 1155 1.587e-11 -3.05972 -0.0937068 0.0612327 3.14415e-13 5.63993e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1155 1156 6.22518 -0.0157694 -0.389045 0.00214092 0.12481 0.0146632 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1106 1156 1.587e-11 -3.05972 -0.0937068 0.0612327 3.14415e-13 5.59552e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1156 1157 6.22606 -0.0162395 -0.389155 0.00213145 0.124828 0.0145096 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1107 1157 1.58771e-11 -3.05972 -0.0937068 0.0612327 3.14415e-13 5.55112e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1157 1158 6.22693 -0.0167098 -0.389264 0.00212197 0.124845 0.0143559 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1108 1158 1.58806e-11 -3.05972 -0.0937068 0.0612327 3.14859e-13 5.50671e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1158 1159 6.22779 -0.0171805 -0.389372 0.00211249 0.124863 0.0142023 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1109 1159 1.58806e-11 -3.05972 -0.0937068 0.0612327 3.14859e-13 5.50671e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1159 1160 6.22864 -0.0176514 -0.389479 0.002103 0.12488 0.0140485 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1110 1160 1.58789e-11 -3.05972 -0.0937068 0.0612327 3.14859e-13 5.4623e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1160 1161 6.22948 -0.0181225 -0.389585 0.00209351 0.124897 0.0138948 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1111 1161 1.58824e-11 -3.05972 -0.0937068 0.0612327 3.14859e-13 5.41789e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1161 1162 6.23031 -0.0185939 -0.389689 0.00208401 0.124914 0.0137411 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1112 1162 1.58842e-11 -3.05972 -0.0937068 0.0612327 3.14859e-13 5.37348e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1162 1163 6.23113 -0.0190656 -0.389792 0.00207451 0.124931 0.0135873 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1113 1163 1.58868e-11 -3.05972 -0.0937068 0.0612327 3.14859e-13 5.32907e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1163 1164 6.23194 -0.0195375 -0.389894 0.002065 0.124947 0.0134335 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1114 1164 1.58877e-11 -3.05972 -0.0937068 0.0612327 3.15303e-13 5.28466e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1164 1165 6.23274 -0.0200097 -0.389995 0.00205549 0.124964 0.0132797 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1115 1165 1.58895e-11 -3.05972 -0.0937068 0.0612327 3.15303e-13 5.24025e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1165 1166 6.23353 -0.0204821 -0.390095 0.00204597 0.12498 0.0131258 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1116 1166 1.58948e-11 -3.05972 -0.0937068 0.0612327 3.15303e-13 5.24025e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1166 1167 6.23432 -0.0209548 -0.390194 0.00203645 0.124996 0.012972 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1117 1167 1.58948e-11 -3.05972 -0.0937068 0.0612327 3.15303e-13 5.19584e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1167 1168 6.23509 -0.0214277 -0.390291 0.00202692 0.125012 0.0128181 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1118 1168 1.58948e-11 -3.05972 -0.0937068 0.0612327 3.15303e-13 5.15143e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1168 1169 6.23585 -0.0219008 -0.390388 0.00201738 0.125027 0.0126642 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1119 1169 1.58984e-11 -3.05972 -0.0937068 0.0612327 3.15303e-13 5.10703e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1169 1170 6.23661 -0.0223741 -0.390483 0.00200785 0.125043 0.0125103 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1120 1170 1.59019e-11 -3.05972 -0.0937068 0.0612327 3.15303e-13 5.06262e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1170 1171 6.23736 -0.0228477 -0.390577 0.0019983 0.125058 0.0123564 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1121 1171 1.59019e-11 -3.05972 -0.0937068 0.0612327 3.15303e-13 5.01821e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1171 1172 6.23809 -0.0233216 -0.39067 0.00198876 0.125073 0.0122024 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1122 1172 1.59055e-11 -3.05972 -0.0937068 0.0612327 3.15303e-13 4.9738e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1172 1173 6.23882 -0.0237956 -0.390761 0.0019792 0.125088 0.0120484 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1123 1173 1.59055e-11 -3.05972 -0.0937068 0.0612327 3.15747e-13 4.92939e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1173 1174 6.23954 -0.0242699 -0.390852 0.00196965 0.125102 0.0118944 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1124 1174 1.59082e-11 -3.05972 -0.0937068 0.0612327 3.15747e-13 4.92939e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1174 1175 6.24025 -0.0247444 -0.390941 0.00196009 0.125117 0.0117404 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1125 1175 1.59096e-11 -3.05972 -0.0937068 0.0612327 3.15747e-13 4.88498e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1175 1176 6.24095 -0.0252191 -0.391029 0.00195052 0.125131 0.0115864 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1126 1176 1.59126e-11 -3.05972 -0.0937068 0.0612327 3.15747e-13 4.84057e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1176 1177 6.24164 -0.025694 -0.391116 0.00194095 0.125145 0.0114324 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1127 1177 1.59126e-11 -3.05972 -0.0937068 0.0612327 3.15747e-13 4.79616e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1177 1178 6.24232 -0.0261692 -0.391202 0.00193138 0.125159 0.0112783 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1128 1178 1.59091e-11 -3.05972 -0.0937068 0.0612327 3.15747e-13 4.75175e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1178 1179 6.24299 -0.0266445 -0.391287 0.0019218 0.125173 0.0111242 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1129 1179 1.59162e-11 -3.05972 -0.0937068 0.0612327 3.16192e-13 4.70735e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1179 1180 6.24365 -0.0271201 -0.391371 0.00191221 0.125186 0.0109701 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1130 1180 1.59162e-11 -3.05972 -0.0937068 0.0612327 3.16192e-13 4.66294e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1180 1181 6.2443 -0.0275958 -0.391453 0.00190263 0.1252 0.010816 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1131 1181 1.59268e-11 -3.05972 -0.0937068 0.0612327 3.16192e-13 4.61853e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1181 1182 6.24494 -0.0280718 -0.391534 0.00189304 0.125213 0.0106619 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1132 1182 1.59233e-11 -3.05972 -0.0937068 0.0612327 3.16192e-13 4.61853e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1182 1183 6.24558 -0.028548 -0.391614 0.00188344 0.125226 0.0105077 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1133 1183 1.59233e-11 -3.05972 -0.0937068 0.0612327 3.16192e-13 4.57412e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1183 1184 6.2462 -0.0290243 -0.391693 0.00187384 0.125239 0.0103536 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1134 1184 1.59268e-11 -3.05972 -0.0937068 0.0612327 3.16192e-13 4.52971e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1184 1185 6.24682 -0.0295009 -0.391771 0.00186424 0.125251 0.0101994 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1135 1185 1.59268e-11 -3.05972 -0.0937068 0.0612327 3.16192e-13 4.4853e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1185 1186 6.24742 -0.0299776 -0.391847 0.00185463 0.125264 0.0100452 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1136 1186 1.59304e-11 -3.05972 -0.0937068 0.0612327 3.16192e-13 4.44089e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1186 1187 6.24802 -0.0304545 -0.391923 0.00184502 0.125276 0.00989097 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1137 1187 1.5929e-11 -3.05972 -0.0937068 0.0612327 3.16636e-13 4.39648e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1187 1188 6.24861 -0.0309316 -0.391997 0.00183541 0.125288 0.00973674 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1138 1188 1.59313e-11 -3.05972 -0.0937068 0.0612327 3.16636e-13 4.35207e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1188 1189 6.24918 -0.0314089 -0.39207 0.00182579 0.1253 0.0095825 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1139 1189 1.59357e-11 -3.05972 -0.0937068 0.0612327 3.16636e-13 4.30767e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1189 1190 6.24975 -0.0318864 -0.392142 0.00181617 0.125311 0.00942824 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1140 1190 1.59339e-11 -3.05972 -0.0937068 0.0612327 3.16636e-13 4.30767e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1190 1191 6.25031 -0.032364 -0.392213 0.00180654 0.125323 0.00927397 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1141 1191 1.59339e-11 -3.05972 -0.0937068 0.0612327 3.16636e-13 4.26326e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1191 1192 6.25086 -0.0328418 -0.392282 0.00179691 0.125334 0.00911968 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1142 1192 1.59304e-11 -3.05972 -0.0937068 0.0612327 3.16636e-13 4.21885e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1192 1193 6.2514 -0.0333198 -0.39235 0.00178728 0.125345 0.00896538 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1143 1193 1.59481e-11 -3.05972 -0.0937068 0.0612327 3.16636e-13 4.17444e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1193 1194 6.25193 -0.0337979 -0.392418 0.00177764 0.125356 0.00881107 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1144 1194 1.59375e-11 -3.05972 -0.0937068 0.0612327 3.16636e-13 4.13003e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1194 1195 6.25245 -0.0342762 -0.392484 0.001768 0.125367 0.00865674 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1145 1195 1.5941e-11 -3.05972 -0.0937068 0.0612327 3.1708e-13 4.08562e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1195 1196 6.25296 -0.0347547 -0.392549 0.00175836 0.125377 0.0085024 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1146 1196 1.59446e-11 -3.05972 -0.0937068 0.0612327 3.1708e-13 4.04121e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1196 1197 6.25347 -0.0352333 -0.392612 0.00174871 0.125388 0.00834805 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1147 1197 1.5941e-11 -3.05972 -0.0937068 0.0612327 3.1708e-13 3.9968e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1197 1198 6.25396 -0.0357121 -0.392675 0.00173907 0.125398 0.00819368 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1148 1198 1.59446e-11 -3.05972 -0.0937068 0.0612327 3.1708e-13 3.9968e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1198 1199 6.25444 -0.036191 -0.392736 0.00172941 0.125408 0.0080393 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1149 1199 1.59446e-11 -3.05972 -0.0937068 0.0612327 3.1708e-13 3.95239e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1199 1200 6.25492 -0.0366701 -0.392796 0.00171976 0.125417 0.00788491 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1150 1200 1.59465e-11 -3.05972 -0.0937068 0.0612327 3.1708e-13 3.90799e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1200 1201 6.25538 -0.0371493 -0.392855 0.0017101 0.125427 0.0077305 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1151 1201 1.59464e-11 -3.05972 -0.0937068 0.0612327 3.1708e-13 3.86358e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1201 1202 6.25584 -0.0376287 -0.392913 0.00170044 0.125436 0.00757609 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1152 1202 1.59481e-11 -3.05972 -0.0937068 0.0612327 3.1708e-13 3.81917e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1202 1203 6.25628 -0.0381082 -0.39297 0.00169077 0.125446 0.00742166 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1153 1203 1.59517e-11 -3.05972 -0.0937068 0.0612327 3.1708e-13 3.77476e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1203 1204 6.25672 -0.0385878 -0.393025 0.00168111 0.125455 0.00726722 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1154 1204 1.59588e-11 -3.05972 -0.0937068 0.0612327 3.1708e-13 3.73035e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1204 1205 6.25715 -0.0390676 -0.393079 0.00167144 0.125463 0.00711277 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1155 1205 1.59517e-11 -3.05972 -0.0937068 0.0612327 3.1708e-13 3.73035e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1205 1206 6.25757 -0.0395475 -0.393132 0.00166177 0.125472 0.0069583 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1156 1206 1.59481e-11 -3.05972 -0.0937068 0.0612327 3.17524e-13 3.68594e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1206 1207 6.25797 -0.0400275 -0.393184 0.00165209 0.12548 0.00680383 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1157 1207 1.59481e-11 -3.05972 -0.0937068 0.0612327 3.17524e-13 3.64153e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1207 1208 6.25837 -0.0405077 -0.393235 0.00164241 0.125489 0.00664935 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1158 1208 1.59552e-11 -3.05972 -0.0937068 0.0612327 3.17524e-13 3.59712e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1208 1209 6.25876 -0.040988 -0.393285 0.00163273 0.125497 0.00649486 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1159 1209 1.59552e-11 -3.05972 -0.0937068 0.0612327 3.17524e-13 3.55271e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1209 1210 6.25914 -0.0414684 -0.393333 0.00162305 0.125504 0.00634035 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1160 1210 1.59552e-11 -3.05972 -0.0937068 0.0612327 3.17524e-13 3.5083e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1210 1211 6.25952 -0.0419489 -0.39338 0.00161336 0.125512 0.00618584 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1161 1211 1.59588e-11 -3.05972 -0.0937068 0.0612327 3.17524e-13 3.4639e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1211 1212 6.25988 -0.0424295 -0.393426 0.00160368 0.12552 0.00603132 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1162 1212 1.59592e-11 -3.05972 -0.0937068 0.0612327 3.17524e-13 3.41949e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1212 1213 6.26023 -0.0429103 -0.393471 0.00159399 0.125527 0.00587678 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1163 1213 1.59592e-11 -3.05972 -0.0937068 0.0612327 3.17524e-13 3.41949e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1213 1214 6.26057 -0.0433911 -0.393515 0.0015843 0.125534 0.00572224 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1164 1214 1.59606e-11 -3.05972 -0.0937068 0.0612327 3.17524e-13 3.37508e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1214 1215 6.26091 -0.0438721 -0.393558 0.0015746 0.125541 0.00556769 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1165 1215 1.59623e-11 -3.05972 -0.0937068 0.0612327 3.17968e-13 3.33067e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1215 1216 6.26123 -0.0443532 -0.393599 0.00156491 0.125548 0.00541313 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1166 1216 1.59659e-11 -3.05972 -0.0937068 0.0612327 3.17968e-13 3.28626e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1216 1217 6.26154 -0.0448343 -0.393639 0.00155521 0.125554 0.00525856 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1167 1217 1.59552e-11 -3.05972 -0.0937068 0.0612327 3.17968e-13 3.24185e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1217 1218 6.26185 -0.0453156 -0.393678 0.00154551 0.125561 0.00510399 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1168 1218 1.59623e-11 -3.05972 -0.0937068 0.0612327 3.17968e-13 3.19744e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1218 1219 6.26215 -0.045797 -0.393716 0.0015358 0.125567 0.00494941 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1169 1219 1.59659e-11 -3.05972 -0.0937068 0.0612327 3.17968e-13 3.15303e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1219 1220 6.26243 -0.0462784 -0.393752 0.0015261 0.125573 0.00479481 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1170 1220 1.59659e-11 -3.05972 -0.0937068 0.0612327 3.17968e-13 3.10862e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1220 1221 6.26271 -0.0467599 -0.393788 0.00151639 0.125578 0.00464022 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1171 1221 1.59659e-11 -3.05972 -0.0937068 0.0612327 3.17968e-13 3.10862e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1221 1222 6.26298 -0.0472416 -0.393822 0.00150669 0.125584 0.00448561 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1172 1222 1.59623e-11 -3.05972 -0.0937068 0.0612327 3.17968e-13 3.06422e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1222 1223 6.26324 -0.0477233 -0.393855 0.00149698 0.125589 0.004331 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1173 1223 1.59677e-11 -3.05972 -0.0937068 0.0612327 3.17968e-13 3.01981e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1223 1224 6.26349 -0.048205 -0.393887 0.00148727 0.125595 0.00417638 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1174 1224 1.59659e-11 -3.05972 -0.0937068 0.0612327 3.17968e-13 2.9754e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1224 1225 6.26372 -0.0486869 -0.393918 0.00147755 0.1256 0.00402175 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1175 1225 1.59685e-11 -3.05972 -0.0937068 0.0612327 3.17968e-13 2.93099e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1225 1226 6.26396 -0.0491688 -0.393947 0.00146784 0.125605 0.00386712 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1176 1226 1.59686e-11 -3.05972 -0.0937068 0.0612327 3.18412e-13 2.88658e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1226 1227 6.26418 -0.0496508 -0.393976 0.00145812 0.125609 0.00371248 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1177 1227 1.59712e-11 -3.05972 -0.0937068 0.0612327 3.18412e-13 2.84217e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1227 1228 6.26439 -0.0501329 -0.394003 0.00144841 0.125614 0.00355784 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1178 1228 1.5973e-11 -3.05972 -0.0937068 0.0612327 3.18412e-13 2.79776e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1228 1229 6.26459 -0.050615 -0.394029 0.00143869 0.125618 0.00340319 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1179 1229 1.59694e-11 -3.05972 -0.0937068 0.0612327 3.18412e-13 2.75335e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1229 1230 6.26478 -0.0510972 -0.394054 0.00142897 0.125622 0.00324854 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1180 1230 1.59766e-11 -3.05972 -0.0937068 0.0612327 3.18412e-13 2.75335e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1230 1231 6.26497 -0.0515795 -0.394077 0.00141925 0.125626 0.00309388 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1181 1231 1.59694e-11 -3.05972 -0.0937068 0.0612327 3.18412e-13 2.70894e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1231 1232 6.26514 -0.0520618 -0.3941 0.00140952 0.12563 0.00293921 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1182 1232 1.59766e-11 -3.05972 -0.0937068 0.0612327 3.18412e-13 2.66454e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1232 1233 6.2653 -0.0525442 -0.394121 0.0013998 0.125633 0.00278454 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1183 1233 1.5973e-11 -3.05972 -0.0937068 0.0612327 3.18412e-13 2.62013e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1233 1234 6.26546 -0.0530266 -0.394141 0.00139008 0.125636 0.00262987 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1184 1234 1.59694e-11 -3.05972 -0.0937068 0.0612327 3.18412e-13 2.57572e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1234 1235 6.2656 -0.0535091 -0.39416 0.00138035 0.125639 0.00247519 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1185 1235 1.59712e-11 -3.05972 -0.0937068 0.0612327 3.18412e-13 2.53131e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1235 1236 6.26574 -0.0539916 -0.394178 0.00137062 0.125642 0.00232051 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1186 1236 1.59748e-11 -3.05972 -0.0937068 0.0612327 3.18412e-13 2.4869e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1236 1237 6.26587 -0.0544741 -0.394195 0.0013609 0.125645 0.00216583 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1187 1237 1.59739e-11 -3.05972 -0.0937068 0.0612327 3.18412e-13 2.44249e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1237 1238 6.26598 -0.0549567 -0.39421 0.00135117 0.125648 0.00201114 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1188 1238 1.59734e-11 -3.05972 -0.0937068 0.0612327 3.18412e-13 2.44249e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1238 1239 6.26609 -0.0554394 -0.394224 0.00134144 0.12565 0.00185645 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1189 1239 1.5973e-11 -3.05972 -0.0937068 0.0612327 3.18412e-13 2.39808e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1239 1240 6.26619 -0.055922 -0.394237 0.00133171 0.125652 0.00170175 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1190 1240 1.59712e-11 -3.05972 -0.0937068 0.0612327 3.18856e-13 2.35367e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1240 1241 6.26628 -0.0564047 -0.394249 0.00132198 0.125654 0.00154706 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1191 1241 1.5973e-11 -3.05972 -0.0937068 0.0612327 3.18856e-13 2.30926e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1241 1242 6.26636 -0.0568874 -0.39426 0.00131225 0.125656 0.00139236 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1192 1242 1.59766e-11 -3.05972 -0.0937068 0.0612327 3.18856e-13 2.26485e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1242 1243 6.26643 -0.0573702 -0.394269 0.00130252 0.125658 0.00123766 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1193 1243 1.59694e-11 -3.05972 -0.0937068 0.0612327 3.18856e-13 2.22045e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1243 1244 6.26649 -0.057853 -0.394277 0.00129279 0.125659 0.00108295 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1194 1244 1.5973e-11 -3.05972 -0.0937068 0.0612327 3.18856e-13 2.17604e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1244 1245 6.26654 -0.0583357 -0.394284 0.00128305 0.12566 0.00092825 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1195 1245 1.59766e-11 -3.05972 -0.0937068 0.0612327 3.18856e-13 2.13163e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1245 1246 6.26659 -0.0588185 -0.39429 0.00127332 0.125661 0.000773544 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1196 1246 1.5973e-11 -3.05972 -0.0937068 0.0612327 3.18856e-13 2.13163e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1246 1247 6.26662 -0.0593014 -0.394295 0.00126359 0.125662 0.000618837 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1197 1247 1.59766e-11 -3.05972 -0.0937068 0.0612327 3.18856e-13 2.08722e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1247 1248 6.26664 -0.0597842 -0.394299 0.00125385 0.125663 0.000464128 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1198 1248 1.5973e-11 -3.05972 -0.0937068 0.0612327 3.18856e-13 2.04281e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1248 1249 6.26666 -0.060267 -0.394301 0.00124412 0.125663 0.000309419 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1199 1249 1.59757e-11 -3.05972 -0.0937068 0.0612327 3.18856e-13 1.9984e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1249 1250 6.26666 -0.0607499 -0.394302 0.00123439 0.125664 0.00015471 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1200 1250 1.59755e-11 -3.05972 -0.0937068 0.0612327 3.18856e-13 1.95399e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1250 1251 6.26666 -0.0612327 -0.394302 0.00122465 0.125664 -4.88498e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1201 1251 1.59766e-11 -3.05972 -0.0937068 0.0612327 3.18856e-13 1.90958e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1251 1252 6.26664 -0.0617155 -0.394301 0.00121492 0.125664 -0.00015471 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1202 1252 1.5973e-11 -3.05972 -0.0937068 0.0612327 3.18856e-13 1.86517e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1252 1253 6.26662 -0.0621984 -0.394299 0.00120519 0.125663 -0.000309419 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1203 1253 1.59694e-11 -3.05972 -0.0937068 0.0612327 3.18856e-13 1.82077e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1253 1254 6.26659 -0.0626812 -0.394295 0.00119545 0.125663 -0.000464128 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1204 1254 1.5973e-11 -3.05972 -0.0937068 0.0612327 3.18856e-13 1.82077e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1254 1255 6.26654 -0.063164 -0.39429 0.00118572 0.125662 -0.000618837 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1205 1255 1.59766e-11 -3.05972 -0.0937068 0.0612327 3.18856e-13 1.77636e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1255 1256 6.26649 -0.0636468 -0.394284 0.00117599 0.125661 -0.000773544 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1206 1256 1.59766e-11 -3.05972 -0.0937068 0.0612327 3.18856e-13 1.73195e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1256 1257 6.26643 -0.0641296 -0.394277 0.00116626 0.12566 -0.00092825 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1207 1257 1.59801e-11 -3.05972 -0.0937068 0.0612327 3.18856e-13 1.68754e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1257 1258 6.26636 -0.0646124 -0.394269 0.00115652 0.125659 -0.00108295 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1208 1258 1.59694e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 1.64313e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1258 1259 6.26628 -0.0650951 -0.39426 0.00114679 0.125658 -0.00123766 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1209 1259 1.59766e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 1.59872e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1259 1260 6.26619 -0.0655778 -0.394249 0.00113706 0.125656 -0.00139236 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1210 1260 1.59766e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 1.55431e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1260 1261 6.26609 -0.0660605 -0.394237 0.00112733 0.125654 -0.00154706 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1211 1261 1.59748e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 1.5099e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1261 1262 6.26598 -0.0665432 -0.394224 0.0011176 0.125652 -0.00170175 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1212 1262 1.59726e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 1.46549e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1262 1263 6.26587 -0.0670258 -0.39421 0.00110787 0.12565 -0.00185645 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1213 1263 1.59734e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 1.46549e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1263 1264 6.26574 -0.0675084 -0.394195 0.00109814 0.125648 -0.00201114 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1214 1264 1.59748e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 1.42109e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1264 1265 6.2656 -0.067991 -0.394178 0.00108841 0.125645 -0.00216583 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1215 1265 1.5973e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 1.37668e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1265 1266 6.26546 -0.0684735 -0.39416 0.00107868 0.125642 -0.00232051 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1216 1266 1.59659e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 1.33227e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1266 1267 6.2653 -0.0689559 -0.394141 0.00106896 0.125639 -0.00247519 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1217 1267 1.5973e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 1.28786e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1267 1268 6.26514 -0.0694384 -0.394121 0.00105923 0.125636 -0.00262987 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1218 1268 1.59766e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 1.24345e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1268 1269 6.26497 -0.0699207 -0.3941 0.00104951 0.125633 -0.00278454 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1219 1269 1.59694e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 1.19904e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1269 1270 6.26478 -0.070403 -0.394077 0.00103978 0.12563 -0.00293921 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1220 1270 1.5973e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 1.15463e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1270 1271 6.26459 -0.0708853 -0.394054 0.00103006 0.125626 -0.00309388 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1221 1271 1.59659e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 1.15463e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1271 1272 6.26439 -0.0713675 -0.394029 0.00102034 0.125622 -0.00324854 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1222 1272 1.5973e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 1.11022e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1272 1273 6.26418 -0.0718496 -0.394003 0.00101062 0.125618 -0.00340319 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1223 1273 1.59694e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 1.06581e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1273 1274 6.26396 -0.0723317 -0.393976 0.0010009 0.125614 -0.00355784 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1224 1274 1.59694e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 1.02141e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1274 1275 6.26372 -0.0728137 -0.393947 0.000991186 0.125609 -0.00371248 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1225 1275 1.59675e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 9.76996e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1275 1276 6.26349 -0.0732956 -0.393918 0.00098147 0.125605 -0.00386712 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1226 1276 1.59677e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 9.32587e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1276 1277 6.26324 -0.0737775 -0.393887 0.000971756 0.1256 -0.00402175 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1227 1277 1.59623e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 8.88178e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1277 1278 6.26298 -0.0742593 -0.393855 0.000962043 0.125595 -0.00417638 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1228 1278 1.59659e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 8.43769e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1278 1279 6.26271 -0.074741 -0.393822 0.000952332 0.125589 -0.004331 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1229 1279 1.59659e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 7.99361e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1279 1280 6.26243 -0.0752226 -0.393788 0.000942622 0.125584 -0.00448561 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1230 1280 1.59659e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 7.99361e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1280 1281 6.26215 -0.0757041 -0.393752 0.000932914 0.125578 -0.00464022 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1231 1281 1.59588e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 7.54952e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1281 1282 6.26185 -0.0761856 -0.393716 0.000923208 0.125573 -0.00479481 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1232 1282 1.59588e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 7.10543e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1282 1283 6.26154 -0.0766669 -0.393678 0.000913504 0.125567 -0.00494941 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1233 1283 1.59588e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 6.66134e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1283 1284 6.26123 -0.0771482 -0.393639 0.000903802 0.125561 -0.00510399 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1234 1284 1.59588e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 6.21725e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1284 1285 6.26091 -0.0776294 -0.393599 0.000894102 0.125554 -0.00525856 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1235 1285 1.59606e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 5.77316e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1285 1286 6.26057 -0.0781104 -0.393558 0.000884403 0.125548 -0.00541313 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1236 1286 1.59606e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 5.32907e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1286 1287 6.26023 -0.0785914 -0.393515 0.000874707 0.125541 -0.00556769 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1237 1287 1.59588e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 4.88498e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1287 1288 6.25988 -0.0790723 -0.393471 0.000865013 0.125534 -0.00572224 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1238 1288 1.5957e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 4.88498e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1288 1289 6.25952 -0.079553 -0.393426 0.000855321 0.125527 -0.00587678 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1239 1289 1.5957e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 4.44089e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1289 1290 6.25914 -0.0800336 -0.39338 0.000845631 0.12552 -0.00603132 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1240 1290 1.5957e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 3.9968e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1290 1291 6.25876 -0.0805142 -0.393333 0.000835943 0.125512 -0.00618584 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1241 1291 1.59517e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 3.55271e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1291 1292 6.25837 -0.0809946 -0.393285 0.000826258 0.125504 -0.00634035 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1242 1292 1.59552e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 3.10862e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1292 1293 6.25797 -0.0814749 -0.393235 0.000816576 0.125497 -0.00649486 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1243 1293 1.59481e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 2.66454e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1293 1294 6.25757 -0.081955 -0.393184 0.000806896 0.125489 -0.00664935 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1244 1294 1.59481e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 2.22045e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1294 1295 6.25715 -0.0824351 -0.393132 0.000797218 0.12548 -0.00680383 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1245 1295 1.59481e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 1.77636e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1295 1296 6.25672 -0.082915 -0.393079 0.000787543 0.125472 -0.0069583 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1246 1296 1.59517e-11 -3.05972 -0.0937068 0.0612327 3.19744e-13 1.77636e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1296 1297 6.25628 -0.0833947 -0.393025 0.00077787 0.125463 -0.00711277 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1247 1297 1.59517e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 1.33227e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1297 1298 6.25584 -0.0838744 -0.39297 0.000768201 0.125455 -0.00726722 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1248 1298 1.59499e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 8.88178e-16 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1298 1299 6.25538 -0.0843539 -0.392913 0.000758534 0.125446 -0.00742166 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1249 1299 1.59455e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 4.44089e-16 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1299 1300 6.25492 -0.0848333 -0.392855 0.00074887 0.125436 -0.00757609 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1250 1300 1.59445e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 0 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1300 1301 6.25444 -0.0853125 -0.392796 0.000739208 0.125427 -0.0077305 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1251 1301 1.59419e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 -4.44089e-16 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1301 1302 6.25396 -0.0857915 -0.392736 0.00072955 0.125417 -0.00788491 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1252 1302 1.5941e-11 -3.05972 -0.0937068 0.0612327 3.19744e-13 -8.88178e-16 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1302 1303 6.25347 -0.0862705 -0.392675 0.000719895 0.125408 -0.0080393 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1253 1303 1.59481e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 -1.33227e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1303 1304 6.25296 -0.0867493 -0.392612 0.000710243 0.125398 -0.00819368 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1254 1304 1.59375e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 -1.77636e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1304 1305 6.25245 -0.0872279 -0.392549 0.000700594 0.125388 -0.00834805 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1255 1305 1.59375e-11 -3.05972 -0.0937068 0.0612327 3.19744e-13 -1.77636e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1305 1306 6.25193 -0.0877063 -0.392484 0.000690948 0.125377 -0.0085024 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1256 1306 1.5941e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 -2.22045e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1306 1307 6.2514 -0.0881846 -0.392418 0.000681305 0.125367 -0.00865674 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1257 1307 1.59339e-11 -3.05972 -0.0937068 0.0612327 3.19744e-13 -2.66454e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1307 1308 6.25086 -0.0886628 -0.39235 0.000671666 0.125356 -0.00881107 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1258 1308 1.59339e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 -3.10862e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1308 1309 6.25031 -0.0891408 -0.392282 0.00066203 0.125345 -0.00896538 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1259 1309 1.59304e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 -3.55271e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1309 1310 6.24975 -0.0896186 -0.392213 0.000652397 0.125334 -0.00911968 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1260 1310 1.59304e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 -3.9968e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1310 1311 6.24918 -0.0900962 -0.392142 0.000642768 0.125323 -0.00927397 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1261 1311 1.59304e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 -4.44089e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1311 1312 6.24861 -0.0905737 -0.39207 0.000633142 0.125311 -0.00942824 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1262 1312 1.59281e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 -4.88498e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1312 1313 6.24802 -0.0910509 -0.391997 0.00062352 0.1253 -0.0095825 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1263 1313 1.59268e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 -4.88498e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1313 1314 6.24742 -0.091528 -0.391923 0.000613902 0.125288 -0.00973674 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1264 1314 1.59268e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 -5.32907e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1314 1315 6.24682 -0.092005 -0.391847 0.000604288 0.125276 -0.00989097 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1265 1315 1.59233e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 -5.77316e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1315 1316 6.2462 -0.0924817 -0.391771 0.000594677 0.125264 -0.0100452 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1266 1316 1.59268e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 -6.21725e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1316 1317 6.24558 -0.0929582 -0.391693 0.00058507 0.125251 -0.0101994 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1267 1317 1.59197e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 -6.66134e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1317 1318 6.24494 -0.0934346 -0.391614 0.000575466 0.125239 -0.0103536 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1268 1318 1.59197e-11 -3.05972 -0.0937068 0.0612327 3.19744e-13 -7.10543e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1318 1319 6.2443 -0.0939107 -0.391534 0.000565867 0.125226 -0.0105077 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1269 1319 1.59197e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 -7.54952e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1319 1320 6.24365 -0.0943867 -0.391453 0.000556272 0.125213 -0.0106619 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1270 1320 1.59162e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 -7.99361e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1320 1321 6.24299 -0.0948625 -0.391371 0.000546681 0.1252 -0.010816 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1271 1321 1.59197e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 -8.43769e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1321 1322 6.24232 -0.095338 -0.391287 0.000537094 0.125186 -0.0109701 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1272 1322 1.59126e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 -8.43769e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1322 1323 6.24164 -0.0958134 -0.391202 0.000527511 0.125173 -0.0111242 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1273 1323 1.59108e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 -8.88178e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1323 1324 6.24095 -0.0962885 -0.391116 0.000517932 0.125159 -0.0112783 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1274 1324 1.59082e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 -9.32587e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1324 1325 6.24025 -0.0967634 -0.391029 0.000508358 0.125145 -0.0114324 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1275 1325 1.59066e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 -9.76996e-15 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1325 1326 6.23954 -0.0972381 -0.390941 0.000498788 0.125131 -0.0115864 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1276 1326 1.59046e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 -1.02141e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1326 1327 6.23882 -0.0977126 -0.390852 0.000489222 0.125117 -0.0117404 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1277 1327 1.59037e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 -1.06581e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1327 1328 6.23809 -0.0981869 -0.390761 0.000479661 0.125102 -0.0118944 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1278 1328 1.58984e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 -1.11022e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1328 1329 6.23736 -0.098661 -0.39067 0.000470105 0.125088 -0.0120484 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1279 1329 1.58984e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 -1.15463e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1329 1330 6.23661 -0.0991348 -0.390577 0.000460553 0.125073 -0.0122024 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1280 1330 1.58913e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 -1.15463e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1330 1331 6.23585 -0.0996084 -0.390483 0.000451005 0.125058 -0.0123564 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1281 1331 1.58948e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 -1.19904e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1331 1332 6.23509 -0.100082 -0.390388 0.000441462 0.125043 -0.0125103 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1282 1332 1.59019e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 -1.24345e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1332 1333 6.23432 -0.100555 -0.390291 0.000431925 0.125027 -0.0126642 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1283 1333 1.58948e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 -1.28786e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1333 1334 6.23353 -0.101028 -0.390194 0.000422391 0.125012 -0.0128181 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1284 1334 1.58842e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 -1.33227e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1334 1335 6.23274 -0.1015 -0.390095 0.000412863 0.124996 -0.012972 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1285 1335 1.58877e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 -1.37668e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1335 1336 6.23194 -0.101973 -0.389995 0.00040334 0.12498 -0.0131258 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1286 1336 1.58842e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 -1.42109e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1336 1337 6.23113 -0.102445 -0.389894 0.000393821 0.124964 -0.0132797 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1287 1337 1.58833e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 -1.46549e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1337 1338 6.23031 -0.102917 -0.389792 0.000384308 0.124947 -0.0134335 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1288 1338 1.58815e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 -1.46549e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1338 1339 6.22948 -0.103389 -0.389689 0.0003748 0.124931 -0.0135873 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1289 1339 1.58789e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 -1.5099e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1339 1340 6.22864 -0.10386 -0.389585 0.000365297 0.124914 -0.0137411 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1290 1340 1.58753e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 -1.55431e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1340 1341 6.22779 -0.104331 -0.389479 0.000355799 0.124897 -0.0138948 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1291 1341 1.58771e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 -1.59872e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1341 1342 6.22693 -0.104802 -0.389372 0.000346306 0.12488 -0.0140485 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1292 1342 1.587e-11 -3.05972 -0.0937068 0.0612327 3.193e-13 -1.64313e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1342 1343 6.22606 -0.105273 -0.389264 0.000336819 0.124863 -0.0142023 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1293 1343 1.58771e-11 -3.05972 -0.0937068 0.0612327 3.18856e-13 -1.68754e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1343 1344 6.22518 -0.105743 -0.389155 0.000327337 0.124845 -0.0143559 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1294 1344 1.587e-11 -3.05972 -0.0937068 0.0612327 3.18856e-13 -1.73195e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1344 1345 6.2243 -0.106213 -0.389045 0.000317861 0.124828 -0.0145096 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1295 1345 1.58664e-11 -3.05972 -0.0937068 0.0612327 3.18856e-13 -1.77636e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1345 1346 6.2234 -0.106683 -0.388934 0.00030839 0.12481 -0.0146632 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1296 1346 1.58593e-11 -3.05972 -0.0937068 0.0612327 3.18856e-13 -1.82077e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1346 1347 6.2225 -0.107153 -0.388821 0.000298925 0.124792 -0.0148169 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1297 1347 1.58629e-11 -3.05972 -0.0937068 0.0612327 3.18856e-13 -1.82077e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1347 1348 6.22158 -0.107622 -0.388708 0.000289465 0.124773 -0.0149705 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1298 1348 1.58575e-11 -3.05972 -0.0937068 0.0612327 3.18856e-13 -1.86517e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1348 1349 6.22066 -0.108091 -0.388593 0.000280011 0.124755 -0.015124 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1299 1349 1.58558e-11 -3.05972 -0.0937068 0.0612327 3.18856e-13 -1.90958e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1349 1350 6.21973 -0.10856 -0.388477 0.000270563 0.124736 -0.0152776 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1300 1350 1.58538e-11 -3.05972 -0.0937068 0.0612327 3.18856e-13 -1.95399e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1350 1351 6.21879 -0.109028 -0.38836 0.00026112 0.124718 -0.0154311 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1301 1351 1.58504e-11 -3.05972 -0.0937068 0.0612327 3.18856e-13 -1.9984e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1351 1352 6.21783 -0.109496 -0.388242 0.000251683 0.124699 -0.0155846 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1302 1352 1.58487e-11 -3.05972 -0.0937068 0.0612327 3.18856e-13 -2.04281e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1352 1353 6.21687 -0.109964 -0.388122 0.000242253 0.124679 -0.0157381 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1303 1353 1.58451e-11 -3.05972 -0.0937068 0.0612327 3.18856e-13 -2.08722e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1353 1354 6.2159 -0.110431 -0.388002 0.000232828 0.12466 -0.0158915 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1304 1354 1.58451e-11 -3.05972 -0.0937068 0.0612327 3.18856e-13 -2.13163e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1354 1355 6.21492 -0.110899 -0.38788 0.000223409 0.124641 -0.016045 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1305 1355 1.58451e-11 -3.05972 -0.0937068 0.0612327 3.18856e-13 -2.13163e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1355 1356 6.21393 -0.111366 -0.387757 0.000213996 0.124621 -0.0161984 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1306 1356 1.5838e-11 -3.05972 -0.0937068 0.0612327 3.18856e-13 -2.17604e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1356 1357 6.21294 -0.111832 -0.387633 0.00020459 0.124601 -0.0163518 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1307 1357 1.58344e-11 -3.05972 -0.0937068 0.0612327 3.18856e-13 -2.22045e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1357 1358 6.21193 -0.112299 -0.387508 0.000195189 0.124581 -0.0165051 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1308 1358 1.58344e-11 -3.05972 -0.0937068 0.0612327 3.18856e-13 -2.26485e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1358 1359 6.21091 -0.112765 -0.387382 0.000185795 0.12456 -0.0166584 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1309 1359 1.58344e-11 -3.05972 -0.0937068 0.0612327 3.18856e-13 -2.30926e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1359 1360 6.20989 -0.11323 -0.387255 0.000176407 0.12454 -0.0168117 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1310 1360 1.58273e-11 -3.05972 -0.0937068 0.0612327 3.18856e-13 -2.35367e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1360 1361 6.20885 -0.113696 -0.387126 0.000167026 0.124519 -0.016965 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1311 1361 1.58256e-11 -3.05972 -0.0937068 0.0612327 3.18856e-13 -2.39808e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1361 1362 6.20781 -0.114161 -0.386997 0.000157651 0.124498 -0.0171183 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1312 1362 1.58233e-11 -3.05972 -0.0937068 0.0612327 3.18412e-13 -2.44249e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1362 1363 6.20675 -0.114626 -0.386866 0.000148282 0.124477 -0.0172715 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1313 1363 1.58207e-11 -3.05972 -0.0937068 0.0612327 3.18412e-13 -2.44249e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1363 1364 6.20569 -0.11509 -0.386734 0.00013892 0.124456 -0.0174247 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1314 1364 1.58167e-11 -3.05972 -0.0937068 0.0612327 3.18412e-13 -2.4869e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1364 1365 6.20462 -0.115554 -0.386601 0.000129565 0.124435 -0.0175779 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1315 1365 1.58149e-11 -3.05972 -0.0937068 0.0612327 3.18412e-13 -2.53131e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1365 1366 6.20353 -0.116018 -0.386467 0.000120216 0.124413 -0.017731 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1316 1366 1.58131e-11 -3.05972 -0.0937068 0.0612327 3.18412e-13 -2.57572e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1366 1367 6.20244 -0.116482 -0.386331 0.000110874 0.124391 -0.0178841 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1317 1367 1.58131e-11 -3.05972 -0.0937068 0.0612327 3.18412e-13 -2.62013e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1367 1368 6.20134 -0.116945 -0.386195 0.000101538 0.124369 -0.0180372 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1318 1368 1.5806e-11 -3.05972 -0.0937068 0.0612327 3.18412e-13 -2.66454e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1368 1369 6.20023 -0.117408 -0.386057 9.22099e-05 0.124347 -0.0181903 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1319 1369 1.57989e-11 -3.05972 -0.0937068 0.0612327 3.18412e-13 -2.70894e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1369 1370 6.19911 -0.11787 -0.385918 8.28882e-05 0.124325 -0.0183433 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1320 1370 1.58025e-11 -3.05972 -0.0937068 0.0612327 3.18412e-13 -2.75335e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1370 1371 6.19799 -0.118332 -0.385778 7.35735e-05 0.124302 -0.0184963 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1321 1371 1.57954e-11 -3.05972 -0.0937068 0.0612327 3.18412e-13 -2.75335e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1371 1372 6.19685 -0.118794 -0.385637 6.42657e-05 0.124279 -0.0186493 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1322 1372 1.57954e-11 -3.05972 -0.0937068 0.0612327 3.18412e-13 -2.79776e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1372 1373 6.1957 -0.119255 -0.385495 5.4965e-05 0.124256 -0.0188022 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1323 1373 1.57936e-11 -3.05972 -0.0937068 0.0612327 3.18412e-13 -2.84217e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1373 1374 6.19454 -0.119717 -0.385352 4.56714e-05 0.124233 -0.0189552 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1324 1374 1.579e-11 -3.05972 -0.0937068 0.0612327 3.17968e-13 -2.88658e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1374 1375 6.19338 -0.120177 -0.385208 3.63849e-05 0.12421 -0.019108 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1325 1375 1.57861e-11 -3.05972 -0.0937068 0.0612327 3.17968e-13 -2.93099e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1375 1376 6.1922 -0.120638 -0.385062 2.71057e-05 0.124187 -0.0192609 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1326 1376 1.57838e-11 -3.05972 -0.0937068 0.0612327 3.17968e-13 -2.9754e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1376 1377 6.19102 -0.121098 -0.384915 1.78337e-05 0.124163 -0.0194137 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1327 1377 1.57812e-11 -3.05972 -0.0937068 0.0612327 3.17968e-13 -3.01981e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1377 1378 6.18983 -0.121557 -0.384768 8.569e-06 0.124139 -0.0195665 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1328 1378 1.57776e-11 -3.05972 -0.0937068 0.0612327 3.17968e-13 -3.06422e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1378 1379 6.18862 -0.122017 -0.384619 -6.88288e-07 0.124115 -0.0197193 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1329 1379 1.5774e-11 -3.05972 -0.0937068 0.0612327 3.17968e-13 -3.10862e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1379 1380 6.18741 -0.122476 -0.384469 -9.93815e-06 0.124091 -0.019872 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1330 1380 1.57705e-11 -3.05972 -0.0937068 0.0612327 3.17968e-13 -3.10862e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1380 1381 6.18619 -0.122934 -0.384318 -1.91805e-05 0.124066 -0.0200247 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1331 1381 1.5774e-11 -3.05972 -0.0937068 0.0612327 3.17968e-13 -3.15303e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1381 1382 6.18496 -0.123392 -0.384165 -2.84153e-05 0.124042 -0.0201774 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1332 1382 1.57563e-11 -3.05972 -0.0937068 0.0612327 3.17968e-13 -3.19744e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1382 1383 6.18372 -0.12385 -0.384012 -3.76426e-05 0.124017 -0.0203301 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1333 1383 1.57634e-11 -3.05972 -0.0937068 0.0612327 3.17968e-13 -3.24185e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1383 1384 6.18247 -0.124308 -0.383857 -4.68621e-05 0.123992 -0.0204827 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1334 1384 1.57634e-11 -3.05972 -0.0937068 0.0612327 3.17968e-13 -3.28626e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1384 1385 6.18121 -0.124765 -0.383702 -5.6074e-05 0.123967 -0.0206353 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1335 1385 1.57563e-11 -3.05972 -0.0937068 0.0612327 3.17968e-13 -3.33067e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1385 1386 6.17994 -0.125221 -0.383545 -6.5278e-05 0.123941 -0.0207878 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1336 1386 1.5751e-11 -3.05972 -0.0937068 0.0612327 3.17524e-13 -3.37508e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1386 1387 6.17867 -0.125678 -0.383387 -7.44743e-05 0.123916 -0.0209403 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1337 1387 1.57474e-11 -3.05972 -0.0937068 0.0612327 3.17524e-13 -3.41949e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1387 1388 6.17738 -0.126134 -0.383228 -8.36627e-05 0.12389 -0.0210928 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1338 1388 1.57452e-11 -3.05972 -0.0937068 0.0612327 3.17524e-13 -3.41949e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1388 1389 6.17609 -0.126589 -0.383068 -9.28431e-05 0.123864 -0.0212453 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1339 1389 1.57421e-11 -3.05972 -0.0937068 0.0612327 3.17524e-13 -3.4639e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1389 1390 6.17478 -0.127044 -0.382907 -0.000102016 0.123838 -0.0213977 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1340 1390 1.57385e-11 -3.05972 -0.0937068 0.0612327 3.17524e-13 -3.5083e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1390 1391 6.17347 -0.127499 -0.382744 -0.00011118 0.123812 -0.0215501 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1341 1391 1.57385e-11 -3.05972 -0.0937068 0.0612327 3.17524e-13 -3.55271e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1391 1392 6.17214 -0.127953 -0.382581 -0.000120336 0.123785 -0.0217024 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1342 1392 1.5735e-11 -3.05972 -0.0937068 0.0612327 3.17524e-13 -3.59712e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1392 1393 6.17081 -0.128407 -0.382416 -0.000129484 0.123759 -0.0218547 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1343 1393 1.57279e-11 -3.05972 -0.0937068 0.0612327 3.17524e-13 -3.64153e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1393 1394 6.16947 -0.128861 -0.382251 -0.000138624 0.123732 -0.022007 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1344 1394 1.57208e-11 -3.05972 -0.0937068 0.0612327 3.17524e-13 -3.68594e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1394 1395 6.16812 -0.129314 -0.382084 -0.000147756 0.123705 -0.0221593 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1345 1395 1.57243e-11 -3.05972 -0.0937068 0.0612327 3.17524e-13 -3.73035e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1395 1396 6.16676 -0.129767 -0.381916 -0.000156879 0.123677 -0.0223115 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1346 1396 1.57208e-11 -3.05972 -0.0937068 0.0612327 3.1708e-13 -3.73035e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1396 1397 6.16539 -0.130219 -0.381747 -0.000165994 0.12365 -0.0224637 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1347 1397 1.57101e-11 -3.05972 -0.0937068 0.0612327 3.1708e-13 -3.77476e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1397 1398 6.16401 -0.130671 -0.381577 -0.000175101 0.123622 -0.0226158 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1348 1398 1.57119e-11 -3.05972 -0.0937068 0.0612327 3.1708e-13 -3.81917e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1398 1399 6.16262 -0.131122 -0.381406 -0.000184199 0.123595 -0.022768 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1349 1399 1.57083e-11 -3.05972 -0.0937068 0.0612327 3.1708e-13 -3.86358e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1399 1400 6.16122 -0.131573 -0.381233 -0.000193288 0.123567 -0.02292 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1350 1400 1.57037e-11 -3.05972 -0.0937068 0.0612327 3.1708e-13 -3.90799e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1400 1401 6.15982 -0.132024 -0.38106 -0.000202369 0.123538 -0.0230721 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1351 1401 1.57003e-11 -3.05972 -0.0937068 0.0612327 3.1708e-13 -3.95239e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1401 1402 6.1584 -0.132474 -0.380885 -0.000211441 0.12351 -0.0232241 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1352 1402 1.56941e-11 -3.05972 -0.0937068 0.0612327 3.1708e-13 -3.9968e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1402 1403 6.15698 -0.132924 -0.38071 -0.000220505 0.123482 -0.0233761 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1353 1403 1.56959e-11 -3.05972 -0.0937068 0.0612327 3.1708e-13 -4.04121e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1403 1404 6.15554 -0.133373 -0.380533 -0.000229559 0.123453 -0.023528 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1354 1404 1.56888e-11 -3.05972 -0.0937068 0.0612327 3.1708e-13 -4.04121e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1404 1405 6.1541 -0.133822 -0.380355 -0.000238605 0.123424 -0.0236799 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1355 1405 1.56817e-11 -3.05972 -0.0937068 0.0612327 3.1708e-13 -4.08562e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1405 1406 6.15265 -0.134271 -0.380176 -0.000247642 0.123395 -0.0238318 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1356 1406 1.56817e-11 -3.05972 -0.0937068 0.0612327 3.16636e-13 -4.13003e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1406 1407 6.15119 -0.134719 -0.379996 -0.00025667 0.123366 -0.0239836 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1357 1407 1.56746e-11 -3.05972 -0.0937068 0.0612327 3.16636e-13 -4.17444e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1407 1408 6.14971 -0.135166 -0.379815 -0.00026569 0.123336 -0.0241354 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1358 1408 1.56746e-11 -3.05972 -0.0937068 0.0612327 3.16636e-13 -4.21885e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1408 1409 6.14823 -0.135613 -0.379633 -0.0002747 0.123307 -0.0242871 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1359 1409 1.5671e-11 -3.05972 -0.0937068 0.0612327 3.16636e-13 -4.26326e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1409 1410 6.14674 -0.13606 -0.37945 -0.000283701 0.123277 -0.0244388 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1360 1410 1.56675e-11 -3.05972 -0.0937068 0.0612327 3.16636e-13 -4.30767e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1410 1411 6.14525 -0.136506 -0.379265 -0.000292692 0.123247 -0.0245905 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1361 1411 1.56621e-11 -3.05972 -0.0937068 0.0612327 3.16636e-13 -4.30767e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1411 1412 6.14374 -0.136952 -0.37908 -0.000301675 0.123216 -0.0247422 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1362 1412 1.56595e-11 -3.05972 -0.0937068 0.0612327 3.16636e-13 -4.35207e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1412 1413 6.14222 -0.137397 -0.378893 -0.000310648 0.123186 -0.0248938 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1363 1413 1.56555e-11 -3.05972 -0.0937068 0.0612327 3.16636e-13 -4.39648e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1413 1414 6.14069 -0.137842 -0.378705 -0.000319612 0.123155 -0.0250453 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1364 1414 1.56515e-11 -3.05972 -0.0937068 0.0612327 3.16192e-13 -4.44089e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1414 1415 6.13916 -0.138287 -0.378517 -0.000328567 0.123125 -0.0251968 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1365 1415 1.56479e-11 -3.05972 -0.0937068 0.0612327 3.16192e-13 -4.4853e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1415 1416 6.13761 -0.13873 -0.378327 -0.000337512 0.123094 -0.0253483 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1366 1416 1.56462e-11 -3.05972 -0.0937068 0.0612327 3.16192e-13 -4.52971e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1416 1417 6.13606 -0.139174 -0.378136 -0.000346448 0.123063 -0.0254998 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1367 1417 1.56426e-11 -3.05972 -0.0937068 0.0612327 3.16192e-13 -4.57412e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1417 1418 6.1345 -0.139617 -0.377944 -0.000355375 0.123031 -0.0256512 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1368 1418 1.56355e-11 -3.05972 -0.0937068 0.0612327 3.16192e-13 -4.61853e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1418 1419 6.13292 -0.140059 -0.377751 -0.000364291 0.123 -0.0258025 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1369 1419 1.56319e-11 -3.05972 -0.0937068 0.0612327 3.16192e-13 -4.61853e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1419 1420 6.13134 -0.140502 -0.377556 -0.000373198 0.122968 -0.0259539 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1370 1420 1.56284e-11 -3.05972 -0.0937068 0.0612327 3.16192e-13 -4.66294e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1420 1421 6.12975 -0.140943 -0.377361 -0.000382096 0.122936 -0.0261052 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1371 1421 1.56213e-11 -3.05972 -0.0937068 0.0612327 3.15747e-13 -4.70735e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1421 1422 6.12815 -0.141384 -0.377165 -0.000390983 0.122904 -0.0262564 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1372 1422 1.56213e-11 -3.05972 -0.0937068 0.0612327 3.15747e-13 -4.75175e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1422 1423 6.12654 -0.141825 -0.376967 -0.000399861 0.122872 -0.0264076 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1373 1423 1.56142e-11 -3.05972 -0.0937068 0.0612327 3.15747e-13 -4.79616e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1423 1424 6.12492 -0.142265 -0.376769 -0.000408729 0.12284 -0.0265588 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1374 1424 1.56097e-11 -3.05972 -0.0937068 0.0612327 3.15747e-13 -4.84057e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1424 1425 6.1233 -0.142705 -0.376569 -0.000417587 0.122807 -0.0267099 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1375 1425 1.56065e-11 -3.05972 -0.0937068 0.0612327 3.15747e-13 -4.88498e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1425 1426 6.12166 -0.143144 -0.376369 -0.000426435 0.122774 -0.026861 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1376 1426 1.56017e-11 -3.05972 -0.0937068 0.0612327 3.15747e-13 -4.92939e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1426 1427 6.12001 -0.143582 -0.376167 -0.000435273 0.122741 -0.027012 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1377 1427 1.55982e-11 -3.05972 -0.0937068 0.0612327 3.15747e-13 -4.92939e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1427 1428 6.11836 -0.144021 -0.375964 -0.000444101 0.122708 -0.027163 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1378 1428 1.55893e-11 -3.05972 -0.0937068 0.0612327 3.15303e-13 -4.9738e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1428 1429 6.11669 -0.144458 -0.37576 -0.000452919 0.122675 -0.027314 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1379 1429 1.55858e-11 -3.05972 -0.0937068 0.0612327 3.15747e-13 -5.01821e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1429 1430 6.11502 -0.144895 -0.375555 -0.000461727 0.122641 -0.0274649 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1380 1430 1.55822e-11 -3.05972 -0.0937068 0.0612327 3.15303e-13 -5.06262e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1430 1431 6.11334 -0.145332 -0.375349 -0.000470524 0.122607 -0.0276158 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1381 1431 1.55786e-11 -3.05972 -0.0937068 0.0612327 3.15303e-13 -5.10703e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1431 1432 6.11165 -0.145768 -0.375142 -0.000479312 0.122573 -0.0277666 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1382 1432 1.55822e-11 -3.05972 -0.0937068 0.0612327 3.15303e-13 -5.15143e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1432 1433 6.10994 -0.146204 -0.374934 -0.000488089 0.122539 -0.0279174 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1383 1433 1.55751e-11 -3.05972 -0.0937068 0.0612327 3.15303e-13 -5.19584e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1433 1434 6.10823 -0.146639 -0.374724 -0.000496855 0.122505 -0.0280681 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1384 1434 1.5568e-11 -3.05972 -0.0937068 0.0612327 3.15303e-13 -5.24025e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1434 1435 6.10651 -0.147074 -0.374514 -0.000505611 0.122471 -0.0282188 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1385 1435 1.55609e-11 -3.05972 -0.0937068 0.0612327 3.15303e-13 -5.24025e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1435 1436 6.10479 -0.147508 -0.374303 -0.000514357 0.122436 -0.0283695 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1386 1436 1.55573e-11 -3.05972 -0.0937068 0.0612327 3.15303e-13 -5.28466e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1436 1437 6.10305 -0.147941 -0.37409 -0.000523092 0.122401 -0.0285201 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1387 1437 1.55547e-11 -3.05972 -0.0937068 0.0612327 3.14859e-13 -5.32907e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1437 1438 6.1013 -0.148375 -0.373877 -0.000531816 0.122366 -0.0286707 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1388 1438 1.55502e-11 -3.05972 -0.0937068 0.0612327 3.14859e-13 -5.37348e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1438 1439 6.09955 -0.148807 -0.373662 -0.00054053 0.122331 -0.0288212 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1389 1439 1.55502e-11 -3.05972 -0.0937068 0.0612327 3.14859e-13 -5.41789e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1439 1440 6.09778 -0.149239 -0.373447 -0.000549233 0.122296 -0.0289717 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1390 1440 1.55413e-11 -3.05972 -0.0937068 0.0612327 3.14859e-13 -5.4623e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1440 1441 6.09601 -0.149671 -0.37323 -0.000557925 0.12226 -0.0291221 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1391 1441 1.5536e-11 -3.05972 -0.0937068 0.0612327 3.14859e-13 -5.50671e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1441 1442 6.09422 -0.150102 -0.373012 -0.000566607 0.122224 -0.0292725 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1392 1442 1.55289e-11 -3.05972 -0.0937068 0.0612327 3.14415e-13 -5.50671e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1442 1443 6.09243 -0.150532 -0.372793 -0.000575278 0.122188 -0.0294228 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1393 1443 1.55289e-11 -3.05972 -0.0937068 0.0612327 3.14415e-13 -5.55112e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1443 1444 6.09063 -0.150962 -0.372574 -0.000583937 0.122152 -0.0295731 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1394 1444 1.55218e-11 -3.05972 -0.0937068 0.0612327 3.14415e-13 -5.59552e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1444 1445 6.08882 -0.151391 -0.372353 -0.000592586 0.122116 -0.0297234 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1395 1445 1.55218e-11 -3.05972 -0.0937068 0.0612327 3.14415e-13 -5.63993e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1445 1446 6.087 -0.15182 -0.372131 -0.000601224 0.122079 -0.0298736 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1396 1446 1.55147e-11 -3.05972 -0.0937068 0.0612327 3.14415e-13 -5.68434e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1446 1447 6.08517 -0.152248 -0.371908 -0.000609851 0.122043 -0.0300238 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1397 1447 1.55076e-11 -3.05972 -0.0937068 0.0612327 3.14415e-13 -5.72875e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1447 1448 6.08333 -0.152676 -0.371684 -0.000618466 0.122006 -0.0301739 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1398 1448 1.55058e-11 -3.05972 -0.0937068 0.0612327 3.14415e-13 -5.77316e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1448 1449 6.08148 -0.153103 -0.371459 -0.00062707 0.121969 -0.0303239 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1399 1449 1.54978e-11 -3.05972 -0.0937068 0.0612327 3.14415e-13 -5.81757e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1449 1450 6.07963 -0.15353 -0.371233 -0.000635664 0.121932 -0.030474 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1400 1450 1.54947e-11 -3.05972 -0.0937068 0.0612327 3.13971e-13 -5.81757e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1450 1451 6.07776 -0.153956 -0.371005 -0.000644246 0.121894 -0.0306239 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1401 1451 1.54898e-11 -3.05972 -0.0937068 0.0612327 3.13971e-13 -5.86198e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1451 1452 6.07589 -0.154381 -0.370777 -0.000652816 0.121857 -0.0307739 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1402 1452 1.54863e-11 -3.05972 -0.0937068 0.0612327 3.13971e-13 -5.90639e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1452 1453 6.074 -0.154806 -0.370548 -0.000661375 0.121819 -0.0309237 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1403 1453 1.54792e-11 -3.05972 -0.0937068 0.0612327 3.13971e-13 -5.9508e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1453 1454 6.07211 -0.155231 -0.370318 -0.000669923 0.121781 -0.0310736 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1404 1454 1.54756e-11 -3.05972 -0.0937068 0.0612327 3.13527e-13 -5.9952e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1454 1455 6.07021 -0.155654 -0.370086 -0.000678459 0.121743 -0.0312234 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1405 1455 1.54685e-11 -3.05972 -0.0937068 0.0612327 3.13527e-13 -6.03961e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1455 1456 6.0683 -0.156078 -0.369854 -0.000686984 0.121704 -0.0313731 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1406 1456 1.54543e-11 -3.05972 -0.0937068 0.0612327 3.13527e-13 -6.08402e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1456 1457 6.06638 -0.1565 -0.36962 -0.000695497 0.121666 -0.0315228 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1407 1457 1.54614e-11 -3.05972 -0.0937068 0.0612327 3.13527e-13 -6.12843e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1457 1458 6.06445 -0.156922 -0.369386 -0.000703999 0.121627 -0.0316724 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1408 1458 1.54543e-11 -3.05972 -0.0937068 0.0612327 3.13527e-13 -6.12843e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1458 1459 6.06251 -0.157344 -0.369151 -0.000712488 0.121588 -0.031822 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1409 1459 1.54472e-11 -3.05972 -0.0937068 0.0612327 3.13527e-13 -6.17284e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1459 1460 6.06056 -0.157765 -0.368914 -0.000720967 0.121549 -0.0319716 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1410 1460 1.54454e-11 -3.05972 -0.0937068 0.0612327 3.13527e-13 -6.21725e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1460 1461 6.05861 -0.158185 -0.368676 -0.000729433 0.12151 -0.032121 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1411 1461 1.54419e-11 -3.05972 -0.0937068 0.0612327 3.13083e-13 -6.26166e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1461 1462 6.05664 -0.158605 -0.368438 -0.000737887 0.121471 -0.0322705 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1412 1462 1.54357e-11 -3.05972 -0.0937068 0.0612327 3.13083e-13 -6.30607e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1462 1463 6.05467 -0.159024 -0.368198 -0.00074633 0.121431 -0.0324199 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1413 1463 1.54312e-11 -3.05972 -0.0937068 0.0612327 3.13083e-13 -6.35048e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1463 1464 6.05268 -0.159443 -0.367958 -0.00075476 0.121391 -0.0325692 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1414 1464 1.54259e-11 -3.05972 -0.0937068 0.0612327 3.13083e-13 -6.39488e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1464 1465 6.05069 -0.159861 -0.367716 -0.000763179 0.121351 -0.0327185 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1415 1465 1.54188e-11 -3.05972 -0.0937068 0.0612327 3.13083e-13 -6.39488e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1465 1466 6.04869 -0.160278 -0.367473 -0.000771585 0.121311 -0.0328678 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1416 1466 1.54117e-11 -3.05972 -0.0937068 0.0612327 3.13083e-13 -6.43929e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1466 1467 6.04668 -0.160695 -0.36723 -0.00077998 0.121271 -0.033017 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1417 1467 1.54046e-11 -3.05972 -0.0937068 0.0612327 3.12639e-13 -6.4837e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1467 1468 6.04466 -0.161111 -0.366985 -0.000788362 0.12123 -0.0331661 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1418 1468 1.54046e-11 -3.05972 -0.0937068 0.0612327 3.12639e-13 -6.52811e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1468 1469 6.04263 -0.161527 -0.366739 -0.000796732 0.12119 -0.0333152 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1419 1469 1.53975e-11 -3.05972 -0.0937068 0.0612327 3.12639e-13 -6.57252e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1469 1470 6.04059 -0.161942 -0.366492 -0.00080509 0.121149 -0.0334642 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1420 1470 1.53975e-11 -3.05972 -0.0937068 0.0612327 3.12639e-13 -6.61693e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1470 1471 6.03854 -0.162356 -0.366245 -0.000813436 0.121108 -0.0336132 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1421 1471 1.53868e-11 -3.05972 -0.0937068 0.0612327 3.12639e-13 -6.66134e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1471 1472 6.03648 -0.16277 -0.365996 -0.000821769 0.121066 -0.0337621 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1422 1472 1.53833e-11 -3.05972 -0.0937068 0.0612327 3.12639e-13 -6.66134e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1472 1473 6.03442 -0.163183 -0.365746 -0.00083009 0.121025 -0.033911 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1423 1473 1.53815e-11 -3.05972 -0.0937068 0.0612327 3.12195e-13 -6.70575e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1473 1474 6.03234 -0.163596 -0.365495 -0.000838398 0.120983 -0.0340599 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1424 1474 1.53726e-11 -3.05972 -0.0937068 0.0612327 3.12195e-13 -6.75016e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1474 1475 6.03026 -0.164008 -0.365244 -0.000846694 0.120942 -0.0342086 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1425 1475 1.53683e-11 -3.05972 -0.0937068 0.0612327 3.12195e-13 -6.79456e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1475 1476 6.02817 -0.164419 -0.364991 -0.000854977 0.1209 -0.0343574 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1426 1476 1.53637e-11 -3.05972 -0.0937068 0.0612327 3.12195e-13 -6.83897e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1476 1477 6.02607 -0.16483 -0.364737 -0.000863248 0.120857 -0.034506 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1427 1477 1.53566e-11 -3.05972 -0.0937068 0.0612327 3.12195e-13 -6.88338e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1477 1478 6.02396 -0.16524 -0.364482 -0.000871506 0.120815 -0.0346546 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1428 1478 1.53548e-11 -3.05972 -0.0937068 0.0612327 3.11751e-13 -6.92779e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1478 1479 6.02184 -0.16565 -0.364226 -0.000879751 0.120773 -0.0348032 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1429 1479 1.53477e-11 -3.05972 -0.0937068 0.0612327 3.11751e-13 -6.92779e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1479 1480 6.01971 -0.166059 -0.363969 -0.000887984 0.12073 -0.0349517 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1430 1480 1.53442e-11 -3.05972 -0.0937068 0.0612327 3.11751e-13 -6.9722e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1480 1481 6.01757 -0.166467 -0.363711 -0.000896203 0.120687 -0.0351002 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1431 1481 1.533e-11 -3.05972 -0.0937068 0.0612327 3.11751e-13 -7.01661e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1481 1482 6.01542 -0.166874 -0.363453 -0.00090441 0.120644 -0.0352486 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1432 1482 1.53264e-11 -3.05972 -0.0937068 0.0612327 3.11751e-13 -7.06102e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1482 1483 6.01327 -0.167281 -0.363193 -0.000912604 0.120601 -0.0353969 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1433 1483 1.533e-11 -3.05972 -0.0937068 0.0612327 3.11751e-13 -7.10543e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1483 1484 6.0111 -0.167688 -0.362932 -0.000920785 0.120557 -0.0355452 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1434 1484 1.53193e-11 -3.05972 -0.0937068 0.0612327 3.11307e-13 -7.14984e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1484 1485 6.00893 -0.168093 -0.36267 -0.000928953 0.120514 -0.0356935 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1435 1485 1.5314e-11 -3.05972 -0.0937068 0.0612327 3.11307e-13 -7.19425e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1485 1486 6.00675 -0.168498 -0.362407 -0.000937109 0.12047 -0.0358416 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1436 1486 1.53086e-11 -3.05972 -0.0937068 0.0612327 3.11307e-13 -7.19425e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1486 1487 6.00455 -0.168903 -0.362144 -0.00094525 0.120426 -0.0359898 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1437 1487 1.5302e-11 -3.05972 -0.0937068 0.0612327 3.11307e-13 -7.23865e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1487 1488 6.00235 -0.169307 -0.361879 -0.000953379 0.120382 -0.0361378 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1438 1488 1.52971e-11 -3.05972 -0.0937068 0.0612327 3.10862e-13 -7.28306e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1488 1489 6.00014 -0.16971 -0.361613 -0.000961495 0.120337 -0.0362859 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1439 1489 1.52891e-11 -3.05972 -0.0937068 0.0612327 3.10862e-13 -7.32747e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1489 1490 5.99793 -0.170112 -0.361346 -0.000969597 0.120293 -0.0364338 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1440 1490 1.52856e-11 -3.05972 -0.0937068 0.0612327 3.10862e-13 -7.37188e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1490 1491 5.9957 -0.170514 -0.361078 -0.000977686 0.120248 -0.0365817 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1441 1491 1.52802e-11 -3.05972 -0.0937068 0.0612327 3.10862e-13 -7.41629e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1491 1492 5.99346 -0.170915 -0.36081 -0.000985762 0.120203 -0.0367296 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1442 1492 1.52767e-11 -3.05972 -0.0937068 0.0612327 3.10862e-13 -7.4607e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1492 1493 5.99121 -0.171315 -0.36054 -0.000993824 0.120158 -0.0368774 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1443 1493 1.5266e-11 -3.05972 -0.0937068 0.0612327 3.10862e-13 -7.4607e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1493 1494 5.98896 -0.171715 -0.360269 -0.00100187 0.120113 -0.0370251 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1444 1494 1.52625e-11 -3.05972 -0.0937068 0.0612327 3.10418e-13 -7.50511e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1494 1495 5.9867 -0.172114 -0.359998 -0.00100991 0.120067 -0.0371728 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1445 1495 1.52554e-11 -3.05972 -0.0937068 0.0612327 3.10418e-13 -7.54952e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1495 1496 5.98442 -0.172513 -0.359725 -0.00101793 0.120022 -0.0373204 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1446 1496 1.52482e-11 -3.05972 -0.0937068 0.0612327 3.10418e-13 -7.59393e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1496 1497 5.98214 -0.172911 -0.359451 -0.00102594 0.119976 -0.037468 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1447 1497 1.52447e-11 -3.05972 -0.0937068 0.0612327 3.10418e-13 -7.63833e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1497 1498 5.97985 -0.173308 -0.359177 -0.00103393 0.11993 -0.0376155 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1448 1498 1.52376e-11 -3.05972 -0.0937068 0.0612327 3.09974e-13 -7.68274e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1498 1499 5.97755 -0.173704 -0.358901 -0.00104191 0.119884 -0.0377629 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1449 1499 1.5234e-11 -3.05972 -0.0937068 0.0612327 3.09974e-13 -7.72715e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1499 1500 5.97524 -0.1741 -0.358624 -0.00104988 0.119838 -0.0379103 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1450 1500 1.52276e-11 -3.05972 -0.0937068 0.0612327 3.09974e-13 -7.72715e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1500 1501 5.97292 -0.174495 -0.358347 -0.00105783 0.119791 -0.0380576 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1451 1501 1.52225e-11 -3.05972 -0.0937068 0.0612327 3.09974e-13 -7.77156e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1501 1502 5.9706 -0.17489 -0.358068 -0.00106577 0.119744 -0.0382049 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1452 1502 1.52163e-11 -3.05972 -0.0937068 0.0612327 3.09974e-13 -7.81597e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1502 1503 5.96826 -0.175283 -0.357789 -0.0010737 0.119698 -0.0383521 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1453 1503 1.52056e-11 -3.05972 -0.0937068 0.0612327 3.0953e-13 -7.86038e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1503 1504 5.96592 -0.175676 -0.357509 -0.00108161 0.119651 -0.0384993 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1454 1504 1.52056e-11 -3.05972 -0.0937068 0.0612327 3.0953e-13 -7.90479e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1504 1505 5.96357 -0.176069 -0.357227 -0.00108951 0.119603 -0.0386464 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1455 1505 1.52056e-11 -3.05972 -0.0937068 0.0612327 3.0953e-13 -7.9492e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1505 1506 5.9612 -0.176461 -0.356945 -0.00109739 0.119556 -0.0387934 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1456 1506 1.5195e-11 -3.05972 -0.0937068 0.0612327 3.0953e-13 -7.99361e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1506 1507 5.95883 -0.176852 -0.356662 -0.00110526 0.119508 -0.0389404 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1457 1507 1.51879e-11 -3.05972 -0.0937068 0.0612327 3.09086e-13 -7.99361e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1507 1508 5.95645 -0.177242 -0.356377 -0.00111312 0.119461 -0.0390873 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1458 1508 1.51807e-11 -3.05972 -0.0937068 0.0612327 3.09086e-13 -8.03801e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1508 1509 5.95406 -0.177631 -0.356092 -0.00112096 0.119413 -0.0392342 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1459 1509 1.51736e-11 -3.05972 -0.0937068 0.0612327 3.09086e-13 -8.08242e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1509 1510 5.95166 -0.17802 -0.355806 -0.00112879 0.119364 -0.039381 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1460 1510 1.51665e-11 -3.05972 -0.0937068 0.0612327 3.09086e-13 -8.12683e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1510 1511 5.94926 -0.178409 -0.355519 -0.0011366 0.119316 -0.0395277 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1461 1511 1.51594e-11 -3.05972 -0.0937068 0.0612327 3.09086e-13 -8.17124e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1511 1512 5.94684 -0.178796 -0.355231 -0.0011444 0.119268 -0.0396744 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1462 1512 1.51554e-11 -3.05972 -0.0937068 0.0612327 3.08642e-13 -8.21565e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1512 1513 5.94442 -0.179183 -0.354942 -0.00115218 0.119219 -0.039821 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1463 1513 1.51483e-11 -3.05972 -0.0937068 0.0612327 3.08642e-13 -8.26006e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1513 1514 5.94198 -0.179569 -0.354652 -0.00115995 0.11917 -0.0399675 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1464 1514 1.51417e-11 -3.05972 -0.0937068 0.0612327 3.08642e-13 -8.26006e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1514 1515 5.93954 -0.179954 -0.354361 -0.00116771 0.119121 -0.040114 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1465 1515 1.51381e-11 -3.05972 -0.0937068 0.0612327 3.08198e-13 -8.30447e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1515 1516 5.93709 -0.180339 -0.354069 -0.00117545 0.119072 -0.0402604 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1466 1516 1.5131e-11 -3.05972 -0.0937068 0.0612327 3.08198e-13 -8.34888e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1516 1517 5.93463 -0.180723 -0.353776 -0.00118318 0.119023 -0.0404068 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1467 1517 1.51203e-11 -3.05972 -0.0937068 0.0612327 3.08198e-13 -8.39329e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1517 1518 5.93216 -0.181106 -0.353482 -0.00119089 0.118973 -0.0405531 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1468 1518 1.51239e-11 -3.05972 -0.0937068 0.0612327 3.08198e-13 -8.43769e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1518 1519 5.92968 -0.181489 -0.353188 -0.00119859 0.118923 -0.0406994 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1469 1519 1.51097e-11 -3.05972 -0.0937068 0.0612327 3.08198e-13 -8.4821e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1519 1520 5.92719 -0.18187 -0.352892 -0.00120627 0.118873 -0.0408455 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1470 1520 1.51026e-11 -3.05972 -0.0937068 0.0612327 3.08198e-13 -8.52651e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1520 1521 5.9247 -0.182251 -0.352596 -0.00121394 0.118823 -0.0409916 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1471 1521 1.5099e-11 -3.05972 -0.0937068 0.0612327 3.07754e-13 -8.52651e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1521 1522 5.92219 -0.182632 -0.352298 -0.00122159 0.118773 -0.0411377 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1472 1522 1.50919e-11 -3.05972 -0.0937068 0.0612327 3.07754e-13 -8.57092e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1522 1523 5.91968 -0.183011 -0.352 -0.00122923 0.118723 -0.0412837 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1473 1523 1.50848e-11 -3.05972 -0.0937068 0.0612327 3.07754e-13 -8.61533e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1523 1524 5.91716 -0.18339 -0.3517 -0.00123685 0.118672 -0.0414296 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1474 1524 1.50804e-11 -3.05972 -0.0937068 0.0612327 3.07754e-13 -8.65974e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1524 1525 5.91462 -0.183768 -0.3514 -0.00124446 0.118621 -0.0415755 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1475 1525 1.50726e-11 -3.05972 -0.0937068 0.0612327 3.0731e-13 -8.70415e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1525 1526 5.91208 -0.184146 -0.351099 -0.00125205 0.11857 -0.0417213 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1476 1526 1.50671e-11 -3.05972 -0.0937068 0.0612327 3.0731e-13 -8.74856e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1526 1527 5.90953 -0.184522 -0.350797 -0.00125963 0.118519 -0.041867 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1477 1527 1.50617e-11 -3.05972 -0.0937068 0.0612327 3.0731e-13 -8.74856e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1527 1528 5.90698 -0.184898 -0.350494 -0.0012672 0.118468 -0.0420127 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1478 1528 1.50528e-11 -3.05972 -0.0937068 0.0612327 3.0731e-13 -8.79297e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1528 1529 5.90441 -0.185273 -0.35019 -0.00127474 0.118416 -0.0421583 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1479 1529 1.50457e-11 -3.05972 -0.0937068 0.0612327 3.0731e-13 -8.83738e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1529 1530 5.90183 -0.185648 -0.349885 -0.00128228 0.118364 -0.0423038 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1480 1530 1.50422e-11 -3.05972 -0.0937068 0.0612327 3.06866e-13 -8.88178e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1530 1531 5.89925 -0.186021 -0.349579 -0.0012898 0.118312 -0.0424493 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1481 1531 1.50351e-11 -3.05972 -0.0937068 0.0612327 3.06866e-13 -8.92619e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1531 1532 5.89665 -0.186394 -0.349273 -0.0012973 0.11826 -0.0425947 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1482 1532 1.50244e-11 -3.05972 -0.0937068 0.0612327 3.06866e-13 -8.9706e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1532 1533 5.89405 -0.186767 -0.348965 -0.00130479 0.118208 -0.04274 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1483 1533 1.50138e-11 -3.05972 -0.0937068 0.0612327 3.06422e-13 -8.9706e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1533 1534 5.89144 -0.187138 -0.348657 -0.00131226 0.118156 -0.0428853 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1484 1534 1.50102e-11 -3.05972 -0.0937068 0.0612327 3.06422e-13 -9.01501e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1534 1535 5.88882 -0.187509 -0.348347 -0.00131972 0.118103 -0.0430305 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1485 1535 1.50049e-11 -3.05972 -0.0937068 0.0612327 3.06422e-13 -9.05942e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1535 1536 5.88619 -0.187879 -0.348037 -0.00132716 0.11805 -0.0431757 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1486 1536 1.49978e-11 -3.05972 -0.0937068 0.0612327 3.06422e-13 -9.10383e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1536 1537 5.88355 -0.188248 -0.347726 -0.00133458 0.117997 -0.0433207 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1487 1537 1.49929e-11 -3.05972 -0.0937068 0.0612327 3.05977e-13 -9.14824e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1537 1538 5.88091 -0.188616 -0.347413 -0.00134199 0.117944 -0.0434658 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1488 1538 1.49858e-11 -3.05972 -0.0937068 0.0612327 3.05977e-13 -9.19265e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1538 1539 5.87825 -0.188984 -0.3471 -0.00134939 0.117891 -0.0436107 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1489 1539 1.49782e-11 -3.05972 -0.0937068 0.0612327 3.05977e-13 -9.23706e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1539 1540 5.87559 -0.18935 -0.346786 -0.00135677 0.117838 -0.0437556 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1490 1540 1.49711e-11 -3.05972 -0.0937068 0.0612327 3.05533e-13 -9.23706e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1540 1541 5.87291 -0.189717 -0.346472 -0.00136413 0.117784 -0.0439004 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1491 1541 1.49605e-11 -3.05972 -0.0937068 0.0612327 3.05533e-13 -9.28146e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1541 1542 5.87023 -0.190082 -0.346156 -0.00137148 0.11773 -0.0440451 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1492 1542 1.49605e-11 -3.05972 -0.0937068 0.0612327 3.05533e-13 -9.32587e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1542 1543 5.86754 -0.190446 -0.345839 -0.00137881 0.117676 -0.0441898 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1493 1543 1.49463e-11 -3.05972 -0.0937068 0.0612327 3.05533e-13 -9.37028e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1543 1544 5.86484 -0.19081 -0.345522 -0.00138613 0.117622 -0.0443344 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1494 1544 1.49498e-11 -3.05972 -0.0937068 0.0612327 3.05533e-13 -9.41469e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1544 1545 5.86213 -0.191173 -0.345203 -0.00139343 0.117567 -0.0444789 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1495 1545 1.49392e-11 -3.05972 -0.0937068 0.0612327 3.05089e-13 -9.4591e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1545 1546 5.85942 -0.191535 -0.344884 -0.00140072 0.117513 -0.0446234 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1496 1546 1.49321e-11 -3.05972 -0.0937068 0.0612327 3.05089e-13 -9.4591e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1546 1547 5.85669 -0.191897 -0.344564 -0.00140799 0.117458 -0.0447678 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1497 1547 1.49267e-11 -3.05972 -0.0937068 0.0612327 3.05089e-13 -9.50351e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1547 1548 5.85396 -0.192257 -0.344243 -0.00141524 0.117403 -0.0449121 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1498 1548 1.49161e-11 -3.05972 -0.0937068 0.0612327 3.04645e-13 -9.54792e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1548 1549 5.85121 -0.192617 -0.343921 -0.00142248 0.117348 -0.0450564 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1499 1549 1.49107e-11 -3.05972 -0.0937068 0.0612327 3.04645e-13 -9.59233e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1549 1550 5.84846 -0.192976 -0.343598 -0.0014297 0.117293 -0.0452006 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1500 1550 1.49034e-11 -3.05972 -0.0937068 0.0612327 3.04645e-13 -9.63674e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1550 1551 5.8457 -0.193334 -0.343274 -0.0014369 0.117238 -0.0453447 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1501 1551 1.48956e-11 -3.05972 -0.0937068 0.0612327 3.04645e-13 -9.68114e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1551 1552 5.84293 -0.193692 -0.34295 -0.00144409 0.117182 -0.0454888 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1502 1552 1.48894e-11 -3.05972 -0.0937068 0.0612327 3.04201e-13 -9.68114e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1552 1553 5.84015 -0.194049 -0.342624 -0.00145126 0.117126 -0.0456328 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1503 1553 1.48859e-11 -3.05972 -0.0937068 0.0612327 3.04201e-13 -9.72555e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1553 1554 5.83736 -0.194404 -0.342298 -0.00145842 0.11707 -0.0457767 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1504 1554 1.48752e-11 -3.05972 -0.0937068 0.0612327 3.04201e-13 -9.76996e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1554 1555 5.83457 -0.194759 -0.341971 -0.00146556 0.117014 -0.0459205 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1505 1555 1.48681e-11 -3.05972 -0.0937068 0.0612327 3.04201e-13 -9.81437e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1555 1556 5.83176 -0.195114 -0.341643 -0.00147269 0.116958 -0.0460643 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1506 1556 1.48539e-11 -3.05972 -0.0937068 0.0612327 3.03757e-13 -9.85878e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1556 1557 5.82895 -0.195467 -0.341314 -0.00147979 0.116901 -0.046208 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1507 1557 1.48503e-11 -3.05972 -0.0937068 0.0612327 3.03757e-13 -9.90319e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1557 1558 5.82613 -0.19582 -0.340984 -0.00148689 0.116845 -0.0463516 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1508 1558 1.48468e-11 -3.05972 -0.0937068 0.0612327 3.03757e-13 -9.9476e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1558 1559 5.8233 -0.196172 -0.340653 -0.00149396 0.116788 -0.0464952 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1509 1559 1.48397e-11 -3.05972 -0.0937068 0.0612327 3.03757e-13 -9.9476e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1559 1560 5.82046 -0.196523 -0.340322 -0.00150102 0.116731 -0.0466387 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1510 1560 1.48326e-11 -3.05972 -0.0937068 0.0612327 3.03313e-13 -9.99201e-14 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1560 1561 5.81761 -0.196873 -0.339989 -0.00150806 0.116674 -0.0467821 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1511 1561 1.4829e-11 -3.05972 -0.0937068 0.0612327 3.03313e-13 -1.00364e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1561 1562 5.81475 -0.197222 -0.339656 -0.00151509 0.116616 -0.0469254 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1512 1562 1.48179e-11 -3.05972 -0.0937068 0.0612327 3.03313e-13 -1.00808e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1562 1563 5.81189 -0.197571 -0.339322 -0.0015221 0.116559 -0.0470687 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1513 1563 1.48104e-11 -3.05972 -0.0937068 0.0612327 3.02869e-13 -1.01252e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1563 1564 5.80901 -0.197919 -0.338987 -0.00152909 0.116501 -0.0472119 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1514 1564 1.48024e-11 -3.05972 -0.0937068 0.0612327 3.02869e-13 -1.01696e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1564 1565 5.80613 -0.198266 -0.338651 -0.00153606 0.116443 -0.047355 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1515 1565 1.47953e-11 -3.05972 -0.0937068 0.0612327 3.02869e-13 -1.01696e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1565 1566 5.80324 -0.198612 -0.338314 -0.00154302 0.116385 -0.0474981 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1516 1566 1.47864e-11 -3.05972 -0.0937068 0.0612327 3.02869e-13 -1.02141e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1566 1567 5.80033 -0.198957 -0.337977 -0.00154997 0.116327 -0.0476411 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1517 1567 1.47864e-11 -3.05972 -0.0937068 0.0612327 3.02425e-13 -1.02585e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1567 1568 5.79743 -0.199302 -0.337639 -0.00155689 0.116268 -0.047784 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1518 1568 1.47757e-11 -3.05972 -0.0937068 0.0612327 3.02425e-13 -1.03029e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1568 1569 5.79451 -0.199645 -0.337299 -0.0015638 0.11621 -0.0479268 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1519 1569 1.47544e-11 -3.05972 -0.0937068 0.0612327 3.02425e-13 -1.03473e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1569 1570 5.79158 -0.199988 -0.336959 -0.00157069 0.116151 -0.0480696 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1520 1570 1.4758e-11 -3.05972 -0.0937068 0.0612327 3.01981e-13 -1.03917e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1570 1571 5.78865 -0.20033 -0.336619 -0.00157757 0.116092 -0.0482122 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1521 1571 1.47509e-11 -3.05972 -0.0937068 0.0612327 3.01981e-13 -1.03917e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1571 1572 5.7857 -0.200671 -0.336277 -0.00158443 0.116033 -0.0483549 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1522 1572 1.4742e-11 -3.05972 -0.0937068 0.0612327 3.01981e-13 -1.04361e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1572 1573 5.78275 -0.201011 -0.335934 -0.00159127 0.115974 -0.0484974 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1523 1573 1.47349e-11 -3.05972 -0.0937068 0.0612327 3.01981e-13 -1.04805e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1573 1574 5.77979 -0.201351 -0.335591 -0.00159809 0.115914 -0.0486399 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1524 1574 1.47269e-11 -3.05972 -0.0937068 0.0612327 3.01537e-13 -1.05249e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1574 1575 5.77682 -0.201689 -0.335247 -0.0016049 0.115855 -0.0487822 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1525 1575 1.47203e-11 -3.05972 -0.0937068 0.0612327 3.01537e-13 -1.05693e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1575 1576 5.77384 -0.202027 -0.334902 -0.00161169 0.115795 -0.0489246 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1526 1576 1.47118e-11 -3.05972 -0.0937068 0.0612327 3.01537e-13 -1.06137e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1576 1577 5.77085 -0.202364 -0.334556 -0.00161846 0.115735 -0.0490668 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1527 1577 1.47011e-11 -3.05972 -0.0937068 0.0612327 3.01092e-13 -1.06137e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1577 1578 5.76785 -0.2027 -0.334209 -0.00162521 0.115675 -0.049209 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1528 1578 1.46958e-11 -3.05972 -0.0937068 0.0612327 3.01092e-13 -1.06581e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1578 1579 5.76485 -0.203035 -0.333862 -0.00163195 0.115614 -0.049351 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1529 1579 1.46905e-11 -3.05972 -0.0937068 0.0612327 3.01092e-13 -1.07025e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1579 1580 5.76184 -0.20337 -0.333513 -0.00163867 0.115554 -0.0494931 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1530 1580 1.46798e-11 -3.05972 -0.0937068 0.0612327 3.01092e-13 -1.0747e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1580 1581 5.75881 -0.203703 -0.333164 -0.00164538 0.115493 -0.049635 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1531 1581 1.46763e-11 -3.05972 -0.0937068 0.0612327 3.00648e-13 -1.07914e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1581 1582 5.75578 -0.204036 -0.332814 -0.00165206 0.115432 -0.0497768 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1532 1582 1.46656e-11 -3.05972 -0.0937068 0.0612327 3.00648e-13 -1.08358e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1582 1583 5.75274 -0.204368 -0.332464 -0.00165873 0.115371 -0.0499186 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1533 1583 1.46585e-11 -3.05972 -0.0937068 0.0612327 3.00648e-13 -1.08358e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1583 1584 5.7497 -0.204699 -0.332112 -0.00166538 0.11531 -0.0500603 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1534 1584 1.46443e-11 -3.05972 -0.0937068 0.0612327 3.00204e-13 -1.08802e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1584 1585 5.74664 -0.205029 -0.33176 -0.00167202 0.115249 -0.050202 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1535 1585 1.46443e-11 -3.05972 -0.0937068 0.0612327 3.00204e-13 -1.09246e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1585 1586 5.74357 -0.205358 -0.331406 -0.00167863 0.115187 -0.0503435 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1536 1586 1.46336e-11 -3.05972 -0.0937068 0.0612327 3.00204e-13 -1.0969e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1586 1587 5.7405 -0.205686 -0.331052 -0.00168523 0.115126 -0.050485 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1537 1587 1.46279e-11 -3.05972 -0.0937068 0.0612327 2.9976e-13 -1.10134e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1587 1588 5.73742 -0.206014 -0.330698 -0.00169181 0.115064 -0.0506264 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1538 1588 1.46199e-11 -3.05972 -0.0937068 0.0612327 2.9976e-13 -1.10578e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1588 1589 5.73433 -0.20634 -0.330342 -0.00169838 0.115002 -0.0507677 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1539 1589 1.46123e-11 -3.05972 -0.0937068 0.0612327 2.9976e-13 -1.10578e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1589 1590 5.73123 -0.206666 -0.329986 -0.00170492 0.114939 -0.0509089 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1540 1590 1.46052e-11 -3.05972 -0.0937068 0.0612327 2.99316e-13 -1.11022e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1590 1591 5.72812 -0.206991 -0.329628 -0.00171145 0.114877 -0.0510501 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1541 1591 1.45945e-11 -3.05972 -0.0937068 0.0612327 2.99316e-13 -1.11466e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1591 1592 5.725 -0.207315 -0.32927 -0.00171796 0.114814 -0.0511912 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1542 1592 1.4591e-11 -3.05972 -0.0937068 0.0612327 2.99316e-13 -1.1191e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1592 1593 5.72188 -0.207638 -0.328912 -0.00172446 0.114752 -0.0513322 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1543 1593 1.45839e-11 -3.05972 -0.0937068 0.0612327 2.99316e-13 -1.12355e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1593 1594 5.71874 -0.20796 -0.328552 -0.00173093 0.114689 -0.0514731 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1544 1594 1.45697e-11 -3.05972 -0.0937068 0.0612327 2.99316e-13 -1.12799e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1594 1595 5.7156 -0.208282 -0.328192 -0.00173739 0.114626 -0.051614 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1545 1595 1.45626e-11 -3.05972 -0.0937068 0.0612327 2.98872e-13 -1.12799e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1595 1596 5.71245 -0.208602 -0.32783 -0.00174383 0.114562 -0.0517547 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1546 1596 1.45555e-11 -3.05972 -0.0937068 0.0612327 2.98872e-13 -1.13243e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1596 1597 5.70929 -0.208922 -0.327469 -0.00175025 0.114499 -0.0518954 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1547 1597 1.4543e-11 -3.05972 -0.0937068 0.0612327 2.98428e-13 -1.13687e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1597 1598 5.70612 -0.209241 -0.327106 -0.00175665 0.114435 -0.052036 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1548 1598 1.45413e-11 -3.05972 -0.0937068 0.0612327 2.98428e-13 -1.14131e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1598 1599 5.70294 -0.209558 -0.326742 -0.00176304 0.114372 -0.0521766 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1549 1599 1.45315e-11 -3.05972 -0.0937068 0.0612327 2.98428e-13 -1.14575e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1599 1600 5.69976 -0.209875 -0.326378 -0.0017694 0.114308 -0.052317 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1550 1600 1.45234e-11 -3.05972 -0.0937068 0.0612327 2.97984e-13 -1.14575e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1600 1601 5.69656 -0.210191 -0.326013 -0.00177575 0.114243 -0.0524574 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1551 1601 1.45155e-11 -3.05972 -0.0937068 0.0612327 2.97984e-13 -1.15019e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1601 1602 5.69336 -0.210506 -0.325647 -0.00178208 0.114179 -0.0525977 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1552 1602 1.45057e-11 -3.05972 -0.0937068 0.0612327 2.97984e-13 -1.15463e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1602 1603 5.69015 -0.210821 -0.325281 -0.0017884 0.114115 -0.0527379 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1553 1603 1.44968e-11 -3.05972 -0.0937068 0.0612327 2.9754e-13 -1.15907e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1603 1604 5.68693 -0.211134 -0.324913 -0.00179469 0.11405 -0.052878 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1554 1604 1.4488e-11 -3.05972 -0.0937068 0.0612327 2.9754e-13 -1.16351e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1604 1605 5.6837 -0.211446 -0.324545 -0.00180097 0.113985 -0.053018 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1555 1605 1.44809e-11 -3.05972 -0.0937068 0.0612327 2.9754e-13 -1.16351e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1605 1606 5.68047 -0.211758 -0.324176 -0.00180722 0.11392 -0.053158 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1556 1606 1.44809e-11 -3.05972 -0.0937068 0.0612327 2.9754e-13 -1.16795e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1606 1607 5.67722 -0.212069 -0.323807 -0.00181346 0.113855 -0.0532979 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1557 1607 1.44667e-11 -3.05972 -0.0937068 0.0612327 2.97096e-13 -1.1724e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1607 1608 5.67397 -0.212378 -0.323436 -0.00181968 0.11379 -0.0534377 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1558 1608 1.4456e-11 -3.05972 -0.0937068 0.0612327 2.97096e-13 -1.17684e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1608 1609 5.6707 -0.212687 -0.323065 -0.00182589 0.113724 -0.0535774 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1559 1609 1.44489e-11 -3.05972 -0.0937068 0.0612327 2.96652e-13 -1.18128e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1609 1610 5.66743 -0.212995 -0.322693 -0.00183207 0.113659 -0.053717 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1560 1610 1.44418e-11 -3.05972 -0.0937068 0.0612327 2.96652e-13 -1.18572e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1610 1611 5.66415 -0.213302 -0.32232 -0.00183824 0.113593 -0.0538566 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1561 1611 1.44329e-11 -3.05972 -0.0937068 0.0612327 2.96652e-13 -1.18572e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1611 1612 5.66087 -0.213608 -0.321947 -0.00184438 0.113527 -0.053996 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1562 1612 1.44236e-11 -3.05972 -0.0937068 0.0612327 2.96652e-13 -1.19016e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1612 1613 5.65757 -0.213913 -0.321573 -0.00185051 0.113461 -0.0541354 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1563 1613 1.4416e-11 -3.05972 -0.0937068 0.0612327 2.96208e-13 -1.1946e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1613 1614 5.65427 -0.214217 -0.321198 -0.00185662 0.113394 -0.0542747 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1564 1614 1.44063e-11 -3.05972 -0.0937068 0.0612327 2.96208e-13 -1.19904e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1614 1615 5.65095 -0.214521 -0.320822 -0.00186272 0.113328 -0.054414 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1565 1615 1.43974e-11 -3.05972 -0.0937068 0.0612327 2.96208e-13 -1.20348e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1615 1616 5.64763 -0.214823 -0.320446 -0.00186879 0.113261 -0.0545531 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1566 1616 1.43885e-11 -3.05972 -0.0937068 0.0612327 2.95763e-13 -1.20792e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1616 1617 5.6443 -0.215125 -0.320069 -0.00187484 0.113194 -0.0546921 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1567 1617 1.43814e-11 -3.05972 -0.0937068 0.0612327 2.95763e-13 -1.20792e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1617 1618 5.64096 -0.215425 -0.319691 -0.00188088 0.113127 -0.0548311 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1568 1618 1.43707e-11 -3.05972 -0.0937068 0.0612327 2.95763e-13 -1.21236e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1618 1619 5.63762 -0.215725 -0.319312 -0.00188689 0.11306 -0.05497 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1569 1619 1.43707e-11 -3.05972 -0.0937068 0.0612327 2.95319e-13 -1.2168e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1619 1620 5.63426 -0.216024 -0.318933 -0.00189289 0.112993 -0.0551088 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1570 1620 1.43601e-11 -3.05972 -0.0937068 0.0612327 2.95319e-13 -1.22125e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1620 1621 5.6309 -0.216321 -0.318553 -0.00189887 0.112925 -0.0552475 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1571 1621 1.43459e-11 -3.05972 -0.0937068 0.0612327 2.95319e-13 -1.22569e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1621 1622 5.62752 -0.216618 -0.318172 -0.00190483 0.112857 -0.0553861 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1572 1622 1.4337e-11 -3.05972 -0.0937068 0.0612327 2.94875e-13 -1.22569e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1622 1623 5.62414 -0.216914 -0.31779 -0.00191077 0.112789 -0.0555247 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1573 1623 1.43316e-11 -3.05972 -0.0937068 0.0612327 2.94875e-13 -1.23013e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1623 1624 5.62075 -0.217209 -0.317408 -0.0019167 0.112721 -0.0556632 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1574 1624 1.43219e-11 -3.05972 -0.0937068 0.0612327 2.94875e-13 -1.23457e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1624 1625 5.61736 -0.217503 -0.317025 -0.0019226 0.112653 -0.0558015 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1575 1625 1.43129e-11 -3.05972 -0.0937068 0.0612327 2.94431e-13 -1.23901e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1625 1626 5.61395 -0.217796 -0.316641 -0.00192848 0.112585 -0.0559398 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1576 1626 1.43059e-11 -3.05972 -0.0937068 0.0612327 2.94431e-13 -1.24345e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1626 1627 5.61054 -0.218088 -0.316257 -0.00193435 0.112516 -0.056078 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1577 1627 1.42979e-11 -3.05972 -0.0937068 0.0612327 2.94431e-13 -1.24345e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1627 1628 5.60711 -0.21838 -0.315872 -0.00194019 0.112448 -0.0562161 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1578 1628 1.4289e-11 -3.05972 -0.0937068 0.0612327 2.93987e-13 -1.24789e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1628 1629 5.60368 -0.21867 -0.315486 -0.00194602 0.112379 -0.0563542 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1579 1629 1.42713e-11 -3.05972 -0.0937068 0.0612327 2.93987e-13 -1.25233e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1629 1630 5.60024 -0.218959 -0.315099 -0.00195183 0.11231 -0.0564921 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1580 1630 1.42677e-11 -3.05972 -0.0937068 0.0612327 2.93987e-13 -1.25677e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1630 1631 5.59679 -0.219247 -0.314712 -0.00195762 0.11224 -0.05663 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1581 1631 1.42606e-11 -3.05972 -0.0937068 0.0612327 2.93543e-13 -1.26121e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1631 1632 5.59334 -0.219535 -0.314324 -0.00196339 0.112171 -0.0567677 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1582 1632 1.42499e-11 -3.05972 -0.0937068 0.0612327 2.93543e-13 -1.26121e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1632 1633 5.58987 -0.219821 -0.313935 -0.00196914 0.112101 -0.0569054 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1583 1633 1.42428e-11 -3.05972 -0.0937068 0.0612327 2.93099e-13 -1.26565e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1633 1634 5.5864 -0.220107 -0.313546 -0.00197487 0.112032 -0.057043 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1584 1634 1.42393e-11 -3.05972 -0.0937068 0.0612327 2.93099e-13 -1.2701e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1634 1635 5.58292 -0.220391 -0.313156 -0.00198058 0.111962 -0.0571805 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1585 1635 1.42233e-11 -3.05972 -0.0937068 0.0612327 2.93099e-13 -1.27454e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1635 1636 5.57943 -0.220675 -0.312765 -0.00198627 0.111892 -0.057318 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1586 1636 1.4218e-11 -3.05972 -0.0937068 0.0612327 2.92655e-13 -1.27898e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1636 1637 5.57593 -0.220958 -0.312374 -0.00199195 0.111821 -0.0574553 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1587 1637 1.42069e-11 -3.05972 -0.0937068 0.0612327 2.92655e-13 -1.28342e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1637 1638 5.57242 -0.221239 -0.311982 -0.0019976 0.111751 -0.0575925 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1588 1638 1.4198e-11 -3.05972 -0.0937068 0.0612327 2.92655e-13 -1.28342e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1638 1639 5.56891 -0.22152 -0.311589 -0.00200323 0.11168 -0.0577297 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1589 1639 1.41913e-11 -3.05972 -0.0937068 0.0612327 2.92211e-13 -1.28786e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1639 1640 5.56538 -0.2218 -0.311195 -0.00200885 0.11161 -0.0578668 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1590 1640 1.41842e-11 -3.05972 -0.0937068 0.0612327 2.92211e-13 -1.2923e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1640 1641 5.56185 -0.222079 -0.310801 -0.00201444 0.111539 -0.0580037 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1591 1641 1.41753e-11 -3.05972 -0.0937068 0.0612327 2.92211e-13 -1.29674e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1641 1642 5.55831 -0.222357 -0.310406 -0.00202002 0.111468 -0.0581406 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1592 1642 1.41647e-11 -3.05972 -0.0937068 0.0612327 2.91767e-13 -1.30118e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1642 1643 5.55476 -0.222633 -0.310011 -0.00202557 0.111396 -0.0582774 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1593 1643 1.41505e-11 -3.05972 -0.0937068 0.0612327 2.91767e-13 -1.30118e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1643 1644 5.55121 -0.222909 -0.309614 -0.00203111 0.111325 -0.0584141 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1594 1644 1.41469e-11 -3.05972 -0.0937068 0.0612327 2.91323e-13 -1.30562e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1644 1645 5.54764 -0.223184 -0.309217 -0.00203663 0.111253 -0.0585508 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1595 1645 1.41362e-11 -3.05972 -0.0937068 0.0612327 2.91323e-13 -1.31006e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1645 1646 5.54407 -0.223458 -0.30882 -0.00204212 0.111182 -0.0586873 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1596 1646 1.41256e-11 -3.05972 -0.0937068 0.0612327 2.91323e-13 -1.3145e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1646 1647 5.54048 -0.223731 -0.308422 -0.0020476 0.11111 -0.0588237 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1597 1647 1.41149e-11 -3.05972 -0.0937068 0.0612327 2.91323e-13 -1.31894e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1647 1648 5.53689 -0.224003 -0.308023 -0.00205306 0.111038 -0.0589601 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1598 1648 1.41043e-11 -3.05972 -0.0937068 0.0612327 2.90878e-13 -1.31894e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1648 1649 5.5333 -0.224274 -0.307623 -0.00205849 0.110965 -0.0590964 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1599 1649 1.40989e-11 -3.05972 -0.0937068 0.0612327 2.90878e-13 -1.32339e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1649 1650 5.52969 -0.224544 -0.307223 -0.00206391 0.110893 -0.0592325 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1600 1650 1.4089e-11 -3.05972 -0.0937068 0.0612327 2.90434e-13 -1.32783e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1650 1651 5.52607 -0.224813 -0.306822 -0.00206931 0.11082 -0.0593686 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1601 1651 1.40794e-11 -3.05972 -0.0937068 0.0612327 2.90434e-13 -1.33227e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1651 1652 5.52245 -0.225081 -0.30642 -0.00207469 0.110748 -0.0595046 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1602 1652 1.40723e-11 -3.05972 -0.0937068 0.0612327 2.90434e-13 -1.33671e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1652 1653 5.51882 -0.225348 -0.306018 -0.00208005 0.110675 -0.0596405 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1603 1653 1.40634e-11 -3.05972 -0.0937068 0.0612327 2.8999e-13 -1.33671e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1653 1654 5.51518 -0.225615 -0.305615 -0.00208538 0.110602 -0.0597763 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1604 1654 1.40545e-11 -3.05972 -0.0937068 0.0612327 2.8999e-13 -1.34115e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1654 1655 5.51153 -0.22588 -0.305212 -0.0020907 0.110529 -0.059912 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1605 1655 1.40403e-11 -3.05972 -0.0937068 0.0612327 2.89546e-13 -1.34559e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1655 1656 5.50788 -0.226144 -0.304807 -0.002096 0.110455 -0.0600476 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1606 1656 1.40332e-11 -3.05972 -0.0937068 0.0612327 2.89546e-13 -1.35003e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1656 1657 5.50421 -0.226407 -0.304403 -0.00210128 0.110382 -0.0601832 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1607 1657 1.40261e-11 -3.05972 -0.0937068 0.0612327 2.89546e-13 -1.35003e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1657 1658 5.50054 -0.226669 -0.303997 -0.00210654 0.110308 -0.0603186 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1608 1658 1.4019e-11 -3.05972 -0.0937068 0.0612327 2.89102e-13 -1.35447e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1658 1659 5.49686 -0.22693 -0.303591 -0.00211177 0.110234 -0.060454 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1609 1659 1.40048e-11 -3.05972 -0.0937068 0.0612327 2.89102e-13 -1.35891e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1659 1660 5.49317 -0.22719 -0.303184 -0.00211699 0.11016 -0.0605892 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1610 1660 1.39941e-11 -3.05972 -0.0937068 0.0612327 2.89102e-13 -1.36335e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1660 1661 5.48947 -0.22745 -0.302777 -0.00212219 0.110086 -0.0607244 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1611 1661 1.3987e-11 -3.05972 -0.0937068 0.0612327 2.88658e-13 -1.36779e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1661 1662 5.48576 -0.227708 -0.302369 -0.00212737 0.110011 -0.0608594 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1612 1662 1.39777e-11 -3.05972 -0.0937068 0.0612327 2.88658e-13 -1.37224e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1662 1663 5.48205 -0.227965 -0.30196 -0.00213252 0.109937 -0.0609944 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1613 1663 1.3967e-11 -3.05972 -0.0937068 0.0612327 2.88658e-13 -1.37224e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1663 1664 5.47833 -0.228221 -0.301551 -0.00213766 0.109862 -0.0611293 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1614 1664 1.39568e-11 -3.05972 -0.0937068 0.0612327 2.88214e-13 -1.37668e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1664 1665 5.4746 -0.228476 -0.301141 -0.00214278 0.109787 -0.0612641 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1615 1665 1.3948e-11 -3.05972 -0.0937068 0.0612327 2.88214e-13 -1.38112e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1665 1666 5.47086 -0.22873 -0.30073 -0.00214787 0.109712 -0.0613988 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1616 1666 1.39337e-11 -3.05972 -0.0937068 0.0612327 2.8777e-13 -1.38556e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1666 1667 5.46711 -0.228984 -0.300319 -0.00215295 0.109637 -0.0615334 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1617 1667 1.39337e-11 -3.05972 -0.0937068 0.0612327 2.8777e-13 -1.39e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1667 1668 5.46336 -0.229236 -0.299907 -0.002158 0.109561 -0.0616679 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1618 1668 1.39195e-11 -3.05972 -0.0937068 0.0612327 2.87326e-13 -1.39e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1668 1669 5.45959 -0.229487 -0.299495 -0.00216304 0.109486 -0.0618023 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1619 1669 1.39089e-11 -3.05972 -0.0937068 0.0612327 2.87326e-13 -1.39444e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1669 1670 5.45582 -0.229737 -0.299082 -0.00216805 0.10941 -0.0619366 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1620 1670 1.38947e-11 -3.05972 -0.0937068 0.0612327 2.87326e-13 -1.39888e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1670 1671 5.45204 -0.229986 -0.298668 -0.00217305 0.109334 -0.0620708 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1621 1671 1.38911e-11 -3.05972 -0.0937068 0.0612327 2.86882e-13 -1.40332e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1671 1672 5.44825 -0.230234 -0.298254 -0.00217802 0.109258 -0.062205 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1622 1672 1.38822e-11 -3.05972 -0.0937068 0.0612327 2.86882e-13 -1.40332e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1672 1673 5.44446 -0.230481 -0.297839 -0.00218297 0.109182 -0.062339 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1623 1673 1.38716e-11 -3.05972 -0.0937068 0.0612327 2.86882e-13 -1.40776e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1673 1674 5.44065 -0.230727 -0.297424 -0.00218791 0.109105 -0.0624729 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1624 1674 1.38627e-11 -3.05972 -0.0937068 0.0612327 2.86438e-13 -1.4122e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1674 1675 5.43684 -0.230972 -0.297008 -0.00219282 0.109029 -0.0626068 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1625 1675 1.38518e-11 -3.05972 -0.0937068 0.0612327 2.86438e-13 -1.41664e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1675 1676 5.43302 -0.231216 -0.296591 -0.00219771 0.108952 -0.0627405 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1626 1676 1.38414e-11 -3.05972 -0.0937068 0.0612327 2.85993e-13 -1.42109e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1676 1677 5.42919 -0.231459 -0.296174 -0.00220258 0.108875 -0.0628741 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1627 1677 1.38325e-11 -3.05972 -0.0937068 0.0612327 2.85993e-13 -1.42109e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1677 1678 5.42535 -0.231701 -0.295756 -0.00220743 0.108798 -0.0630077 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1628 1678 1.38218e-11 -3.05972 -0.0937068 0.0612327 2.85993e-13 -1.42553e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1678 1679 5.42151 -0.231942 -0.295338 -0.00221226 0.108721 -0.0631412 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1629 1679 1.3813e-11 -3.05972 -0.0937068 0.0612327 2.85549e-13 -1.42997e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1679 1680 5.41766 -0.232182 -0.294919 -0.00221707 0.108644 -0.0632745 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1630 1680 1.38023e-11 -3.05972 -0.0937068 0.0612327 2.85549e-13 -1.43441e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1680 1681 5.41379 -0.232421 -0.294499 -0.00222185 0.108566 -0.0634078 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1631 1681 1.37952e-11 -3.05972 -0.0937068 0.0612327 2.85549e-13 -1.43885e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1681 1682 5.40993 -0.232659 -0.294079 -0.00222662 0.108489 -0.0635409 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1632 1682 1.37845e-11 -3.05972 -0.0937068 0.0612327 2.85105e-13 -1.43885e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1682 1683 5.40605 -0.232896 -0.293658 -0.00223137 0.108411 -0.063674 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1633 1683 1.37739e-11 -3.05972 -0.0937068 0.0612327 2.85105e-13 -1.44329e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1683 1684 5.40216 -0.233132 -0.293237 -0.00223609 0.108333 -0.063807 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1634 1684 1.37632e-11 -3.05972 -0.0937068 0.0612327 2.84661e-13 -1.44773e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1684 1685 5.39827 -0.233366 -0.292815 -0.0022408 0.108255 -0.0639398 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1635 1685 1.37561e-11 -3.05972 -0.0937068 0.0612327 2.84661e-13 -1.45217e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1685 1686 5.39437 -0.2336 -0.292393 -0.00224548 0.108176 -0.0640726 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1636 1686 1.37428e-11 -3.05972 -0.0937068 0.0612327 2.84217e-13 -1.45661e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1686 1687 5.39046 -0.233833 -0.291969 -0.00225014 0.108098 -0.0642053 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1637 1687 1.37335e-11 -3.05972 -0.0937068 0.0612327 2.84217e-13 -1.45661e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1687 1688 5.38654 -0.234065 -0.291546 -0.00225478 0.108019 -0.0643379 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1638 1688 1.37232e-11 -3.05972 -0.0937068 0.0612327 2.84217e-13 -1.46105e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1688 1689 5.38261 -0.234295 -0.291122 -0.0022594 0.10794 -0.0644704 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1639 1689 1.37135e-11 -3.05972 -0.0937068 0.0612327 2.83773e-13 -1.46549e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1689 1690 5.37868 -0.234525 -0.290697 -0.002264 0.107861 -0.0646027 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1640 1690 1.3701e-11 -3.05972 -0.0937068 0.0612327 2.83773e-13 -1.46994e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1690 1691 5.37474 -0.234753 -0.290272 -0.00226858 0.107782 -0.064735 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1641 1691 1.36957e-11 -3.05972 -0.0937068 0.0612327 2.83773e-13 -1.47438e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1691 1692 5.37079 -0.234981 -0.289846 -0.00227314 0.107703 -0.0648672 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1642 1692 1.36851e-11 -3.05972 -0.0937068 0.0612327 2.83329e-13 -1.47438e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1692 1693 5.36683 -0.235207 -0.289419 -0.00227768 0.107623 -0.0649993 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1643 1693 1.36708e-11 -3.05972 -0.0937068 0.0612327 2.83329e-13 -1.47882e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1693 1694 5.36286 -0.235433 -0.288992 -0.00228219 0.107544 -0.0651313 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1644 1694 1.36602e-11 -3.05972 -0.0937068 0.0612327 2.82885e-13 -1.48326e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1694 1695 5.35889 -0.235657 -0.288565 -0.00228669 0.107464 -0.0652631 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1645 1695 1.36531e-11 -3.05972 -0.0937068 0.0612327 2.82885e-13 -1.4877e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1695 1696 5.3549 -0.23588 -0.288137 -0.00229116 0.107384 -0.0653949 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1646 1696 1.36495e-11 -3.05972 -0.0937068 0.0612327 2.82441e-13 -1.4877e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1696 1697 5.35091 -0.236103 -0.287708 -0.00229561 0.107304 -0.0655266 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1647 1697 1.36353e-11 -3.05972 -0.0937068 0.0612327 2.82441e-13 -1.49214e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1697 1698 5.34692 -0.236324 -0.287279 -0.00230004 0.107224 -0.0656582 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1648 1698 1.36229e-11 -3.05972 -0.0937068 0.0612327 2.82441e-13 -1.49658e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1698 1699 5.34291 -0.236544 -0.286849 -0.00230445 0.107143 -0.0657897 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1649 1699 1.36113e-11 -3.05972 -0.0937068 0.0612327 2.81997e-13 -1.50102e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1699 1700 5.3389 -0.236763 -0.286419 -0.00230884 0.107063 -0.0659211 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1650 1700 1.36017e-11 -3.05972 -0.0937068 0.0612327 2.81997e-13 -1.50546e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1700 1701 5.33487 -0.236981 -0.285988 -0.0023132 0.106982 -0.0660523 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1651 1701 1.35909e-11 -3.05972 -0.0937068 0.0612327 2.81553e-13 -1.50546e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1701 1702 5.33084 -0.237198 -0.285557 -0.00231755 0.106901 -0.0661835 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1652 1702 1.35802e-11 -3.05972 -0.0937068 0.0612327 2.81553e-13 -1.5099e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1702 1703 5.3268 -0.237414 -0.285125 -0.00232187 0.10682 -0.0663146 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1653 1703 1.35678e-11 -3.05972 -0.0937068 0.0612327 2.81553e-13 -1.51434e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1703 1704 5.32276 -0.237629 -0.284693 -0.00232617 0.106739 -0.0664456 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1654 1704 1.35607e-11 -3.05972 -0.0937068 0.0612327 2.81108e-13 -1.51879e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1704 1705 5.3187 -0.237843 -0.28426 -0.00233046 0.106657 -0.0665765 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1655 1705 1.35536e-11 -3.05972 -0.0937068 0.0612327 2.81108e-13 -1.51879e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1705 1706 5.31464 -0.238056 -0.283826 -0.00233472 0.106576 -0.0667072 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1656 1706 1.35358e-11 -3.05972 -0.0937068 0.0612327 2.80664e-13 -1.52323e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1706 1707 5.31057 -0.238268 -0.283392 -0.00233895 0.106494 -0.0668379 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1657 1707 1.35287e-11 -3.05972 -0.0937068 0.0612327 2.80664e-13 -1.52767e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1707 1708 5.30649 -0.238478 -0.282958 -0.00234317 0.106412 -0.0669685 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1658 1708 1.35181e-11 -3.05972 -0.0937068 0.0612327 2.8022e-13 -1.53211e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1708 1709 5.3024 -0.238688 -0.282523 -0.00234736 0.10633 -0.0670989 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1659 1709 1.35074e-11 -3.05972 -0.0937068 0.0612327 2.8022e-13 -1.53655e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1709 1710 5.29831 -0.238896 -0.282087 -0.00235154 0.106248 -0.0672293 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1660 1710 1.34985e-11 -3.05972 -0.0937068 0.0612327 2.8022e-13 -1.53655e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1710 1711 5.29421 -0.239104 -0.281651 -0.00235569 0.106166 -0.0673596 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1661 1711 1.3487e-11 -3.05972 -0.0937068 0.0612327 2.79776e-13 -1.54099e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1711 1712 5.2901 -0.23931 -0.281215 -0.00235982 0.106083 -0.0674897 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1662 1712 1.34763e-11 -3.05972 -0.0937068 0.0612327 2.79776e-13 -1.54543e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1712 1713 5.28598 -0.239516 -0.280778 -0.00236393 0.106 -0.0676198 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1663 1713 1.34661e-11 -3.05972 -0.0937068 0.0612327 2.79332e-13 -1.54987e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1713 1714 5.28185 -0.23972 -0.28034 -0.00236802 0.105918 -0.0677497 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1664 1714 1.34577e-11 -3.05972 -0.0937068 0.0612327 2.79332e-13 -1.54987e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1714 1715 5.27772 -0.239923 -0.279902 -0.00237208 0.105835 -0.0678796 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1665 1715 1.34452e-11 -3.05972 -0.0937068 0.0612327 2.78888e-13 -1.55431e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1715 1716 5.27358 -0.240125 -0.279464 -0.00237613 0.105751 -0.0680093 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1666 1716 1.34364e-11 -3.05972 -0.0937068 0.0612327 2.78888e-13 -1.55875e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1716 1717 5.26943 -0.240326 -0.279025 -0.00238015 0.105668 -0.068139 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1667 1717 1.34186e-11 -3.05972 -0.0937068 0.0612327 2.78888e-13 -1.56319e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1717 1718 5.26527 -0.240526 -0.278585 -0.00238415 0.105585 -0.0682685 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1668 1718 1.34115e-11 -3.05972 -0.0937068 0.0612327 2.78444e-13 -1.56319e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1718 1719 5.2611 -0.240725 -0.278145 -0.00238813 0.105501 -0.0683979 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1669 1719 1.34044e-11 -3.05972 -0.0937068 0.0612327 2.78444e-13 -1.56763e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1719 1720 5.25693 -0.240923 -0.277705 -0.00239208 0.105417 -0.0685273 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1670 1720 1.33902e-11 -3.05972 -0.0937068 0.0612327 2.78e-13 -1.57208e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1720 1721 5.25275 -0.241119 -0.277264 -0.00239602 0.105333 -0.0686565 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1671 1721 1.3376e-11 -3.05972 -0.0937068 0.0612327 2.78e-13 -1.57652e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1721 1722 5.24856 -0.241315 -0.276823 -0.00239993 0.105249 -0.0687856 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1672 1722 1.33706e-11 -3.05972 -0.0937068 0.0612327 2.78e-13 -1.58096e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1722 1723 5.24436 -0.24151 -0.276381 -0.00240382 0.105165 -0.0689146 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1673 1723 1.336e-11 -3.05972 -0.0937068 0.0612327 2.77556e-13 -1.58096e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1723 1724 5.24016 -0.241703 -0.275938 -0.00240769 0.105081 -0.0690435 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1674 1724 1.33493e-11 -3.05972 -0.0937068 0.0612327 2.77556e-13 -1.5854e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1724 1725 5.23595 -0.241895 -0.275495 -0.00241154 0.104996 -0.0691723 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1675 1725 1.33388e-11 -3.05972 -0.0937068 0.0612327 2.77112e-13 -1.58984e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1725 1726 5.23173 -0.242087 -0.275052 -0.00241537 0.104911 -0.069301 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1676 1726 1.33289e-11 -3.05972 -0.0937068 0.0612327 2.77112e-13 -1.59428e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1726 1727 5.2275 -0.242277 -0.274608 -0.00241917 0.104826 -0.0694296 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1677 1727 1.33173e-11 -3.05972 -0.0937068 0.0612327 2.76668e-13 -1.59428e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1727 1728 5.22326 -0.242466 -0.274164 -0.00242295 0.104741 -0.0695581 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1678 1728 1.33085e-11 -3.05972 -0.0937068 0.0612327 2.76668e-13 -1.59872e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1728 1729 5.21902 -0.242654 -0.273719 -0.00242671 0.104656 -0.0696865 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1679 1729 1.32978e-11 -3.05972 -0.0937068 0.0612327 2.76223e-13 -1.60316e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1729 1730 5.21476 -0.242841 -0.273274 -0.00243045 0.104571 -0.0698148 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1680 1730 1.328e-11 -3.05972 -0.0937068 0.0612327 2.76223e-13 -1.6076e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1730 1731 5.2105 -0.243027 -0.272828 -0.00243416 0.104485 -0.0699429 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1681 1731 1.32694e-11 -3.05972 -0.0937068 0.0612327 2.75779e-13 -1.6076e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1731 1732 5.20624 -0.243212 -0.272382 -0.00243786 0.1044 -0.070071 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1682 1732 1.32694e-11 -3.05972 -0.0937068 0.0612327 2.75779e-13 -1.61204e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1732 1733 5.20196 -0.243395 -0.271936 -0.00244153 0.104314 -0.0701989 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1683 1733 1.32516e-11 -3.05972 -0.0937068 0.0612327 2.75779e-13 -1.61648e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1733 1734 5.19768 -0.243578 -0.271489 -0.00244518 0.104228 -0.0703268 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1684 1734 1.32339e-11 -3.05972 -0.0937068 0.0612327 2.75335e-13 -1.62093e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1734 1735 5.19339 -0.243759 -0.271041 -0.00244881 0.104142 -0.0704545 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1685 1735 1.32321e-11 -3.05972 -0.0937068 0.0612327 2.75335e-13 -1.62093e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1735 1736 5.18909 -0.24394 -0.270594 -0.00245241 0.104055 -0.0705821 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1686 1736 1.32188e-11 -3.05972 -0.0937068 0.0612327 2.74891e-13 -1.62537e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1736 1737 5.18478 -0.244119 -0.270145 -0.002456 0.103969 -0.0707097 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1687 1737 1.32081e-11 -3.05972 -0.0937068 0.0612327 2.74891e-13 -1.62981e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1737 1738 5.18047 -0.244297 -0.269696 -0.00245956 0.103882 -0.0708371 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1688 1738 1.31979e-11 -3.05972 -0.0937068 0.0612327 2.74447e-13 -1.63425e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1738 1739 5.17614 -0.244474 -0.269247 -0.0024631 0.103796 -0.0709644 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1689 1739 1.31877e-11 -3.05972 -0.0937068 0.0612327 2.74447e-13 -1.63425e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1739 1740 5.17181 -0.24465 -0.268798 -0.00246661 0.103709 -0.0710916 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1690 1740 1.3177e-11 -3.05972 -0.0937068 0.0612327 2.74447e-13 -1.63869e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1740 1741 5.16748 -0.244825 -0.268348 -0.00247011 0.103622 -0.0712187 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1691 1741 1.31646e-11 -3.05972 -0.0937068 0.0612327 2.74003e-13 -1.64313e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1741 1742 5.16313 -0.244999 -0.267897 -0.00247358 0.103534 -0.0713457 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1692 1742 1.31486e-11 -3.05972 -0.0937068 0.0612327 2.74003e-13 -1.64757e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1742 1743 5.15878 -0.245172 -0.267446 -0.00247703 0.103447 -0.0714725 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1693 1743 1.31415e-11 -3.05972 -0.0937068 0.0612327 2.73559e-13 -1.64757e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1743 1744 5.15442 -0.245343 -0.266995 -0.00248046 0.103359 -0.0715993 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1694 1744 1.31344e-11 -3.05972 -0.0937068 0.0612327 2.73559e-13 -1.65201e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1744 1745 5.15005 -0.245514 -0.266543 -0.00248386 0.103272 -0.0717259 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1695 1745 1.31166e-11 -3.05972 -0.0937068 0.0612327 2.73115e-13 -1.65645e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1745 1746 5.14567 -0.245683 -0.266091 -0.00248724 0.103184 -0.0718525 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1696 1746 1.3106e-11 -3.05972 -0.0937068 0.0612327 2.73115e-13 -1.66089e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1746 1747 5.14129 -0.245851 -0.265638 -0.0024906 0.103096 -0.0719789 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1697 1747 1.30971e-11 -3.05972 -0.0937068 0.0612327 2.72671e-13 -1.66089e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1747 1748 5.1369 -0.246019 -0.265185 -0.00249394 0.103008 -0.0721052 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1698 1748 1.30864e-11 -3.05972 -0.0937068 0.0612327 2.72671e-13 -1.66533e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1748 1749 5.1325 -0.246185 -0.264732 -0.00249726 0.10292 -0.0722314 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1699 1749 1.30758e-11 -3.05972 -0.0937068 0.0612327 2.72227e-13 -1.66978e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1749 1750 5.12809 -0.246349 -0.264278 -0.00250055 0.102831 -0.0723576 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1700 1750 1.30635e-11 -3.05972 -0.0937068 0.0612327 2.72227e-13 -1.67422e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1750 1751 5.12367 -0.246513 -0.263824 -0.00250382 0.102742 -0.0724835 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1701 1751 1.30527e-11 -3.05972 -0.0937068 0.0612327 2.71783e-13 -1.67422e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1751 1752 5.11925 -0.246676 -0.263369 -0.00250707 0.102654 -0.0726094 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1702 1752 1.30385e-11 -3.05972 -0.0937068 0.0612327 2.71783e-13 -1.67866e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1752 1753 5.11482 -0.246838 -0.262914 -0.0025103 0.102565 -0.0727352 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1703 1753 1.30296e-11 -3.05972 -0.0937068 0.0612327 2.71783e-13 -1.6831e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1753 1754 5.11038 -0.246998 -0.262459 -0.0025135 0.102476 -0.0728609 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1704 1754 1.30171e-11 -3.05972 -0.0937068 0.0612327 2.71339e-13 -1.68754e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1754 1755 5.10594 -0.247157 -0.262003 -0.00251668 0.102386 -0.0729864 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1705 1755 1.30065e-11 -3.05972 -0.0937068 0.0612327 2.71339e-13 -1.68754e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1755 1756 5.10148 -0.247316 -0.261547 -0.00251984 0.102297 -0.0731118 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1706 1756 1.29923e-11 -3.05972 -0.0937068 0.0612327 2.70894e-13 -1.69198e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1756 1757 5.09702 -0.247473 -0.261091 -0.00252297 0.102208 -0.0732372 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1707 1757 1.29852e-11 -3.05972 -0.0937068 0.0612327 2.70894e-13 -1.69642e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1757 1758 5.09255 -0.247629 -0.260634 -0.00252609 0.102118 -0.0733624 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1708 1758 1.2971e-11 -3.05972 -0.0937068 0.0612327 2.7045e-13 -1.70086e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1758 1759 5.08808 -0.247784 -0.260176 -0.00252918 0.102028 -0.0734875 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1709 1759 1.29603e-11 -3.05972 -0.0937068 0.0612327 2.7045e-13 -1.70086e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1759 1760 5.08359 -0.247937 -0.259719 -0.00253225 0.101938 -0.0736125 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1710 1760 1.29496e-11 -3.05972 -0.0937068 0.0612327 2.70006e-13 -1.7053e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1760 1761 5.0791 -0.24809 -0.259261 -0.00253529 0.101848 -0.0737374 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1711 1761 1.2939e-11 -3.05972 -0.0937068 0.0612327 2.70006e-13 -1.70974e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1761 1762 5.0746 -0.248242 -0.258802 -0.00253831 0.101758 -0.0738621 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1712 1762 1.29274e-11 -3.05972 -0.0937068 0.0612327 2.69562e-13 -1.71418e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1762 1763 5.0701 -0.248392 -0.258343 -0.00254131 0.101667 -0.0739868 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1713 1763 1.29163e-11 -3.05972 -0.0937068 0.0612327 2.69562e-13 -1.71418e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1763 1764 5.06558 -0.248541 -0.257884 -0.00254429 0.101577 -0.0741113 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1714 1764 1.29026e-11 -3.05972 -0.0937068 0.0612327 2.69118e-13 -1.71863e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1764 1765 5.06106 -0.248689 -0.257425 -0.00254725 0.101486 -0.0742357 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1715 1765 1.2891e-11 -3.05972 -0.0937068 0.0612327 2.69118e-13 -1.72307e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1765 1766 5.05653 -0.248836 -0.256965 -0.00255018 0.101395 -0.07436 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1716 1766 1.28804e-11 -3.05972 -0.0937068 0.0612327 2.68674e-13 -1.72751e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1766 1767 5.05199 -0.248982 -0.256504 -0.00255309 0.101304 -0.0744842 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1717 1767 1.28715e-11 -3.05972 -0.0937068 0.0612327 2.68674e-13 -1.72751e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1767 1768 5.04745 -0.249127 -0.256044 -0.00255597 0.101213 -0.0746083 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1718 1768 1.28608e-11 -3.05972 -0.0937068 0.0612327 2.6823e-13 -1.73195e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1768 1769 5.0429 -0.249271 -0.255583 -0.00255884 0.101121 -0.0747323 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1719 1769 1.28466e-11 -3.05972 -0.0937068 0.0612327 2.6823e-13 -1.73639e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1769 1770 5.03834 -0.249413 -0.255121 -0.00256168 0.10103 -0.0748562 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1720 1770 1.28324e-11 -3.05972 -0.0937068 0.0612327 2.6823e-13 -1.74083e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1770 1771 5.03377 -0.249555 -0.25466 -0.0025645 0.100938 -0.0749799 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1721 1771 1.28253e-11 -3.05972 -0.0937068 0.0612327 2.67786e-13 -1.74083e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1771 1772 5.0292 -0.249695 -0.254198 -0.00256729 0.100846 -0.0751035 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1722 1772 1.28111e-11 -3.05972 -0.0937068 0.0612327 2.67342e-13 -1.74527e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1772 1773 5.02461 -0.249834 -0.253735 -0.00257006 0.100754 -0.0752271 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1723 1773 1.27987e-11 -3.05972 -0.0937068 0.0612327 2.67342e-13 -1.74971e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1773 1774 5.02002 -0.249972 -0.253273 -0.00257281 0.100662 -0.0753505 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1724 1774 1.2788e-11 -3.05972 -0.0937068 0.0612327 2.67342e-13 -1.75415e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1774 1775 5.01543 -0.250109 -0.25281 -0.00257554 0.10057 -0.0754737 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1725 1775 1.27758e-11 -3.05972 -0.0937068 0.0612327 2.66898e-13 -1.75415e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1775 1776 5.01082 -0.250244 -0.252346 -0.00257825 0.100477 -0.0755969 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1726 1776 1.2764e-11 -3.05972 -0.0937068 0.0612327 2.66898e-13 -1.75859e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1776 1777 5.00621 -0.250379 -0.251883 -0.00258093 0.100385 -0.07572 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1727 1777 1.27525e-11 -3.05972 -0.0937068 0.0612327 2.66454e-13 -1.76303e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1777 1778 5.00159 -0.250512 -0.251418 -0.00258358 0.100292 -0.0758429 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1728 1778 1.27383e-11 -3.05972 -0.0937068 0.0612327 2.66454e-13 -1.76748e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1778 1779 4.99696 -0.250645 -0.250954 -0.00258622 0.100199 -0.0759657 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1729 1779 1.27294e-11 -3.05972 -0.0937068 0.0612327 2.66009e-13 -1.76748e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1779 1780 4.99233 -0.250776 -0.250489 -0.00258883 0.100106 -0.0760884 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1730 1780 1.27223e-11 -3.05972 -0.0937068 0.0612327 2.66009e-13 -1.77192e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1780 1781 4.98768 -0.250906 -0.250024 -0.00259142 0.100013 -0.076211 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1731 1781 1.27081e-11 -3.05972 -0.0937068 0.0612327 2.65565e-13 -1.77636e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1781 1782 4.98303 -0.251035 -0.249559 -0.00259399 0.0999198 -0.0763335 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1732 1782 1.26903e-11 -3.05972 -0.0937068 0.0612327 2.65565e-13 -1.77636e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1782 1783 4.97838 -0.251163 -0.249094 -0.00259653 0.0998264 -0.0764559 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1733 1783 1.26796e-11 -3.05972 -0.0937068 0.0612327 2.65121e-13 -1.7808e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1783 1784 4.97371 -0.251289 -0.248628 -0.00259905 0.0997328 -0.0765781 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1734 1784 1.26725e-11 -3.05972 -0.0937068 0.0612327 2.65121e-13 -1.78524e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1784 1785 4.96904 -0.251415 -0.248161 -0.00260155 0.099639 -0.0767002 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1735 1785 1.26583e-11 -3.05972 -0.0937068 0.0612327 2.64677e-13 -1.78968e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1785 1786 4.96436 -0.251539 -0.247695 -0.00260402 0.0995451 -0.0768223 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1736 1786 1.2645e-11 -3.05972 -0.0937068 0.0612327 2.64677e-13 -1.78968e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1786 1787 4.95967 -0.251662 -0.247228 -0.00260647 0.099451 -0.0769441 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1737 1787 1.26343e-11 -3.05972 -0.0937068 0.0612327 2.64233e-13 -1.79412e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1787 1788 4.95498 -0.251784 -0.246761 -0.0026089 0.0993568 -0.0770659 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1738 1788 1.26206e-11 -3.05972 -0.0937068 0.0612327 2.64233e-13 -1.79856e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1788 1789 4.95027 -0.251905 -0.246293 -0.00261131 0.0992624 -0.0771876 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1739 1789 1.26068e-11 -3.05972 -0.0937068 0.0612327 2.63789e-13 -1.803e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1789 1790 4.94556 -0.252025 -0.245826 -0.00261369 0.0991679 -0.0773091 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1740 1790 1.25979e-11 -3.05972 -0.0937068 0.0612327 2.63789e-13 -1.803e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1790 1791 4.94085 -0.252143 -0.245357 -0.00261605 0.0990733 -0.0774305 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1741 1791 1.25819e-11 -3.05972 -0.0937068 0.0612327 2.63345e-13 -1.80744e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1791 1792 4.93612 -0.252261 -0.244889 -0.00261839 0.0989785 -0.0775519 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1742 1792 1.25695e-11 -3.05972 -0.0937068 0.0612327 2.63345e-13 -1.81188e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1792 1793 4.93139 -0.252377 -0.244421 -0.0026207 0.0988835 -0.077673 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1743 1793 1.25624e-11 -3.05972 -0.0937068 0.0612327 2.62901e-13 -1.81188e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1793 1794 4.92665 -0.252492 -0.243952 -0.00262299 0.0987884 -0.0777941 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1744 1794 1.25446e-11 -3.05972 -0.0937068 0.0612327 2.62901e-13 -1.81632e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1794 1795 4.9219 -0.252606 -0.243482 -0.00262525 0.0986932 -0.0779151 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1745 1795 1.25375e-11 -3.05972 -0.0937068 0.0612327 2.62457e-13 -1.82077e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1795 1796 4.91715 -0.252719 -0.243013 -0.0026275 0.0985978 -0.0780359 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1746 1796 1.25233e-11 -3.05972 -0.0937068 0.0612327 2.62457e-13 -1.82521e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1796 1797 4.91239 -0.252831 -0.242543 -0.00262972 0.0985022 -0.0781566 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1747 1797 1.25127e-11 -3.05972 -0.0937068 0.0612327 2.62013e-13 -1.82521e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1797 1798 4.90762 -0.252942 -0.242073 -0.00263192 0.0984065 -0.0782772 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1748 1798 1.25002e-11 -3.05972 -0.0937068 0.0612327 2.62013e-13 -1.82965e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1798 1799 4.90284 -0.253051 -0.241603 -0.00263409 0.0983107 -0.0783977 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1749 1799 1.24869e-11 -3.05972 -0.0937068 0.0612327 2.61569e-13 -1.83409e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1799 1800 4.89806 -0.253159 -0.241132 -0.00263624 0.0982147 -0.078518 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1750 1800 1.24762e-11 -3.05972 -0.0937068 0.0612327 2.61569e-13 -1.83853e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1800 1801 4.89327 -0.253266 -0.240662 -0.00263837 0.0981186 -0.0786383 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1751 1801 1.24638e-11 -3.05972 -0.0937068 0.0612327 2.61124e-13 -1.83853e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1801 1802 4.88847 -0.253372 -0.240191 -0.00264047 0.0980223 -0.0787584 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1752 1802 1.24505e-11 -3.05972 -0.0937068 0.0612327 2.61124e-13 -1.84297e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1802 1803 4.88367 -0.253477 -0.239719 -0.00264255 0.0979259 -0.0788784 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1753 1803 1.24416e-11 -3.05972 -0.0937068 0.0612327 2.6068e-13 -1.84741e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1803 1804 4.87885 -0.253581 -0.239248 -0.00264461 0.0978293 -0.0789982 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1754 1804 1.24309e-11 -3.05972 -0.0937068 0.0612327 2.6068e-13 -1.84741e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1804 1805 4.87403 -0.253683 -0.238776 -0.00264664 0.0977326 -0.079118 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1755 1805 1.24167e-11 -3.05972 -0.0937068 0.0612327 2.60236e-13 -1.85185e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1805 1806 4.86921 -0.253784 -0.238304 -0.00264866 0.0976357 -0.0792376 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1756 1806 1.24025e-11 -3.05972 -0.0937068 0.0612327 2.60236e-13 -1.85629e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1806 1807 4.86437 -0.253885 -0.237831 -0.00265064 0.0975387 -0.0793572 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1757 1807 1.23954e-11 -3.05972 -0.0937068 0.0612327 2.59792e-13 -1.85629e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1807 1808 4.85953 -0.253984 -0.237359 -0.00265261 0.0974416 -0.0794765 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1758 1808 1.23812e-11 -3.05972 -0.0937068 0.0612327 2.59792e-13 -1.86073e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1808 1809 4.85468 -0.254082 -0.236886 -0.00265455 0.0973443 -0.0795958 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1759 1809 1.23634e-11 -3.05972 -0.0937068 0.0612327 2.59348e-13 -1.86517e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1809 1810 4.84982 -0.254178 -0.236413 -0.00265647 0.0972468 -0.079715 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1760 1810 1.23546e-11 -3.05972 -0.0937068 0.0612327 2.59348e-13 -1.86962e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1810 1811 4.84496 -0.254274 -0.23594 -0.00265836 0.0971492 -0.079834 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1761 1811 1.23386e-11 -3.05972 -0.0937068 0.0612327 2.58904e-13 -1.86962e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1811 1812 4.84009 -0.254368 -0.235466 -0.00266023 0.0970515 -0.0799529 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1762 1812 1.23279e-11 -3.05972 -0.0937068 0.0612327 2.58904e-13 -1.87406e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1812 1813 4.83521 -0.254461 -0.234992 -0.00266208 0.0969536 -0.0800717 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1763 1813 1.23159e-11 -3.05972 -0.0937068 0.0612327 2.5846e-13 -1.8785e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1813 1814 4.83032 -0.254553 -0.234518 -0.00266391 0.0968556 -0.0801904 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1764 1814 1.23039e-11 -3.05972 -0.0937068 0.0612327 2.58016e-13 -1.88294e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1814 1815 4.82543 -0.254644 -0.234044 -0.00266571 0.0967574 -0.0803089 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1765 1815 1.22888e-11 -3.05972 -0.0937068 0.0612327 2.58016e-13 -1.88294e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1815 1816 4.82053 -0.254734 -0.23357 -0.00266748 0.0966591 -0.0804273 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1766 1816 1.22764e-11 -3.05972 -0.0937068 0.0612327 2.57572e-13 -1.88738e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1816 1817 4.81562 -0.254823 -0.233095 -0.00266924 0.0965606 -0.0805456 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1767 1817 1.22675e-11 -3.05972 -0.0937068 0.0612327 2.57572e-13 -1.89182e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1817 1818 4.81071 -0.25491 -0.23262 -0.00267097 0.096462 -0.0806638 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1768 1818 1.22533e-11 -3.05972 -0.0937068 0.0612327 2.57572e-13 -1.89182e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1818 1819 4.80579 -0.254996 -0.232145 -0.00267268 0.0963633 -0.0807819 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1769 1819 1.22391e-11 -3.05972 -0.0937068 0.0612327 2.57128e-13 -1.89626e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1819 1820 4.80086 -0.255081 -0.23167 -0.00267436 0.0962644 -0.0808998 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1770 1820 1.22249e-11 -3.05972 -0.0937068 0.0612327 2.56684e-13 -1.9007e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1820 1821 4.79592 -0.255165 -0.231194 -0.00267602 0.0961653 -0.0810176 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1771 1821 1.22178e-11 -3.05972 -0.0937068 0.0612327 2.56684e-13 -1.90514e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1821 1822 4.79098 -0.255248 -0.230719 -0.00267766 0.0960661 -0.0811353 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1772 1822 1.22036e-11 -3.05972 -0.0937068 0.0612327 2.56239e-13 -1.90514e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1822 1823 4.78603 -0.25533 -0.230243 -0.00267927 0.0959668 -0.0812528 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1773 1823 1.21876e-11 -3.05972 -0.0937068 0.0612327 2.56239e-13 -1.90958e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1823 1824 4.78107 -0.25541 -0.229767 -0.00268086 0.0958674 -0.0813703 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1774 1824 1.21769e-11 -3.05972 -0.0937068 0.0612327 2.55795e-13 -1.91402e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1824 1825 4.77611 -0.255489 -0.22929 -0.00268243 0.0957677 -0.0814876 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1775 1825 1.2165e-11 -3.05972 -0.0937068 0.0612327 2.55795e-13 -1.91402e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1825 1826 4.77113 -0.255567 -0.228814 -0.00268397 0.095668 -0.0816048 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1776 1826 1.21512e-11 -3.05972 -0.0937068 0.0612327 2.55351e-13 -1.91847e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1826 1827 4.76615 -0.255644 -0.228337 -0.00268549 0.0955681 -0.0817219 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1777 1827 1.21396e-11 -3.05972 -0.0937068 0.0612327 2.55351e-13 -1.92291e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1827 1828 4.76117 -0.25572 -0.22786 -0.00268699 0.095468 -0.0818388 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1778 1828 1.2129e-11 -3.05972 -0.0937068 0.0612327 2.54907e-13 -1.92291e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1828 1829 4.75617 -0.255795 -0.227383 -0.00268846 0.0953679 -0.0819556 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1779 1829 1.21183e-11 -3.05972 -0.0937068 0.0612327 2.54907e-13 -1.92735e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1829 1830 4.75117 -0.255868 -0.226906 -0.00268991 0.0952675 -0.0820723 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1780 1830 1.21041e-11 -3.05972 -0.0937068 0.0612327 2.54463e-13 -1.93179e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1830 1831 4.74617 -0.25594 -0.226429 -0.00269134 0.0951671 -0.0821889 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1781 1831 1.20934e-11 -3.05972 -0.0937068 0.0612327 2.54463e-13 -1.93623e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1831 1832 4.74115 -0.256011 -0.225951 -0.00269274 0.0950665 -0.0823053 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1782 1832 1.20757e-11 -3.05972 -0.0937068 0.0612327 2.54019e-13 -1.93623e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1832 1833 4.73613 -0.256081 -0.225473 -0.00269412 0.0949657 -0.0824216 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1783 1833 1.20579e-11 -3.05972 -0.0937068 0.0612327 2.54019e-13 -1.94067e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1833 1834 4.7311 -0.25615 -0.224995 -0.00269547 0.0948648 -0.0825378 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1784 1834 1.20526e-11 -3.05972 -0.0937068 0.0612327 2.53575e-13 -1.94511e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1834 1835 4.72606 -0.256218 -0.224517 -0.0026968 0.0947638 -0.0826539 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1785 1835 1.20384e-11 -3.05972 -0.0937068 0.0612327 2.53131e-13 -1.94511e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1835 1836 4.72102 -0.256284 -0.224039 -0.00269811 0.0946626 -0.0827698 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1786 1836 1.20259e-11 -3.05972 -0.0937068 0.0612327 2.53131e-13 -1.94955e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1836 1837 4.71597 -0.256349 -0.223561 -0.0026994 0.0945613 -0.0828856 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1787 1837 1.20117e-11 -3.05972 -0.0937068 0.0612327 2.52687e-13 -1.95399e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1837 1838 4.71091 -0.256413 -0.223082 -0.00270066 0.0944598 -0.0830013 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1788 1838 1.1998e-11 -3.05972 -0.0937068 0.0612327 2.52687e-13 -1.95399e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1838 1839 4.70585 -0.256476 -0.222603 -0.00270189 0.0943582 -0.0831169 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1789 1839 1.19851e-11 -3.05972 -0.0937068 0.0612327 2.52243e-13 -1.95843e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1839 1840 4.70078 -0.256538 -0.222125 -0.00270311 0.0942565 -0.0832323 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1790 1840 1.19726e-11 -3.05972 -0.0937068 0.0612327 2.52243e-13 -1.96287e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1840 1841 4.6957 -0.256598 -0.221646 -0.0027043 0.0941546 -0.0833476 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1791 1841 1.19584e-11 -3.05972 -0.0937068 0.0612327 2.51799e-13 -1.96287e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1841 1842 4.69061 -0.256658 -0.221166 -0.00270547 0.0940526 -0.0834628 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1792 1842 1.19478e-11 -3.05972 -0.0937068 0.0612327 2.51799e-13 -1.96732e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1842 1843 4.68552 -0.256716 -0.220687 -0.00270661 0.0939504 -0.0835779 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1793 1843 1.19371e-11 -3.05972 -0.0937068 0.0612327 2.51354e-13 -1.97176e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1843 1844 4.68042 -0.256773 -0.220208 -0.00270773 0.0938481 -0.0836928 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1794 1844 1.19229e-11 -3.05972 -0.0937068 0.0612327 2.51354e-13 -1.9762e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1844 1845 4.67531 -0.256829 -0.219728 -0.00270882 0.0937456 -0.0838076 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1795 1845 1.19051e-11 -3.05972 -0.0937068 0.0612327 2.5091e-13 -1.9762e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1845 1846 4.6702 -0.256883 -0.219248 -0.00270989 0.0936431 -0.0839223 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1796 1846 1.18927e-11 -3.05972 -0.0937068 0.0612327 2.50466e-13 -1.98064e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1846 1847 4.66508 -0.256937 -0.218768 -0.00271094 0.0935403 -0.0840368 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1797 1847 1.18821e-11 -3.05972 -0.0937068 0.0612327 2.50466e-13 -1.98508e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1847 1848 4.65995 -0.256989 -0.218288 -0.00271197 0.0934375 -0.0841513 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1798 1848 1.18696e-11 -3.05972 -0.0937068 0.0612327 2.50022e-13 -1.98508e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1848 1849 4.65482 -0.25704 -0.217808 -0.00271297 0.0933345 -0.0842656 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1799 1849 1.18563e-11 -3.05972 -0.0937068 0.0612327 2.50022e-13 -1.98952e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1849 1850 4.64967 -0.25709 -0.217328 -0.00271395 0.0932313 -0.0843797 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1800 1850 1.18423e-11 -3.05972 -0.0937068 0.0612327 2.49578e-13 -1.99396e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1850 1851 4.64453 -0.257139 -0.216848 -0.0027149 0.093128 -0.0844938 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1801 1851 1.18296e-11 -3.05972 -0.0937068 0.0612327 2.49578e-13 -1.99396e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1851 1852 4.63937 -0.257187 -0.216367 -0.00271583 0.0930246 -0.0846077 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1802 1852 1.18181e-11 -3.05972 -0.0937068 0.0612327 2.49134e-13 -1.9984e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1852 1853 4.63421 -0.257233 -0.215887 -0.00271674 0.0929211 -0.0847214 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1803 1853 1.18039e-11 -3.05972 -0.0937068 0.0612327 2.49134e-13 -2.00284e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1853 1854 4.62904 -0.257278 -0.215406 -0.00271762 0.0928174 -0.0848351 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1804 1854 1.17932e-11 -3.05972 -0.0937068 0.0612327 2.4869e-13 -2.00728e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1854 1855 4.62386 -0.257323 -0.214925 -0.00271848 0.0927135 -0.0849486 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1805 1855 1.17737e-11 -3.05972 -0.0937068 0.0612327 2.4869e-13 -2.00728e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1855 1856 4.61868 -0.257365 -0.214444 -0.00271931 0.0926095 -0.085062 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1806 1856 1.17595e-11 -3.05972 -0.0937068 0.0612327 2.48246e-13 -2.01172e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1856 1857 4.61349 -0.257407 -0.213963 -0.00272013 0.0925054 -0.0851753 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1807 1857 1.17524e-11 -3.05972 -0.0937068 0.0612327 2.48246e-13 -2.01617e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1857 1858 4.60829 -0.257448 -0.213482 -0.00272091 0.0924012 -0.0852884 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1808 1858 1.17346e-11 -3.05972 -0.0937068 0.0612327 2.47802e-13 -2.01617e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1858 1859 4.60309 -0.257487 -0.213001 -0.00272168 0.0922968 -0.0854014 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1809 1859 1.17222e-11 -3.05972 -0.0937068 0.0612327 2.47358e-13 -2.02061e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1859 1860 4.59787 -0.257525 -0.212519 -0.00272242 0.0921923 -0.0855143 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1810 1860 1.17115e-11 -3.05972 -0.0937068 0.0612327 2.47358e-13 -2.02505e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1860 1861 4.59266 -0.257562 -0.212038 -0.00272314 0.0920876 -0.085627 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1811 1861 1.16964e-11 -3.05972 -0.0937068 0.0612327 2.46914e-13 -2.02505e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1861 1862 4.58743 -0.257598 -0.211556 -0.00272383 0.0919828 -0.0857397 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1812 1862 1.16835e-11 -3.05972 -0.0937068 0.0612327 2.46914e-13 -2.02949e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1862 1863 4.5822 -0.257633 -0.211075 -0.0027245 0.0918778 -0.0858521 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1813 1863 1.16693e-11 -3.05972 -0.0937068 0.0612327 2.4647e-13 -2.03393e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1863 1864 4.57696 -0.257666 -0.210593 -0.00272514 0.0917728 -0.0859645 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1814 1864 1.16565e-11 -3.05972 -0.0937068 0.0612327 2.4647e-13 -2.03393e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1864 1865 4.57172 -0.257698 -0.210111 -0.00272577 0.0916676 -0.0860767 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1815 1865 1.16422e-11 -3.05972 -0.0937068 0.0612327 2.46025e-13 -2.03837e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1865 1866 4.56646 -0.25773 -0.20963 -0.00272636 0.0915622 -0.0861888 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1816 1866 1.1628e-11 -3.05972 -0.0937068 0.0612327 2.45581e-13 -2.04281e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1866 1867 4.5612 -0.25776 -0.209148 -0.00272694 0.0914567 -0.0863008 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1817 1867 1.16174e-11 -3.05972 -0.0937068 0.0612327 2.45581e-13 -2.04281e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1867 1868 4.55594 -0.257788 -0.208666 -0.00272749 0.0913511 -0.0864126 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1818 1868 1.16032e-11 -3.05972 -0.0937068 0.0612327 2.45581e-13 -2.04725e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1868 1869 4.55067 -0.257816 -0.208184 -0.00272802 0.0912453 -0.0865243 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1819 1869 1.15854e-11 -3.05972 -0.0937068 0.0612327 2.45137e-13 -2.05169e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1869 1870 4.54539 -0.257842 -0.207702 -0.00272852 0.0911394 -0.0866359 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1820 1870 1.15783e-11 -3.05972 -0.0937068 0.0612327 2.44693e-13 -2.05169e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1870 1871 4.5401 -0.257867 -0.207219 -0.002729 0.0910334 -0.0867473 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1821 1871 1.15623e-11 -3.05972 -0.0937068 0.0612327 2.44693e-13 -2.05613e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1871 1872 4.53481 -0.257891 -0.206737 -0.00272946 0.0909272 -0.0868586 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1822 1872 1.15481e-11 -3.05972 -0.0937068 0.0612327 2.44249e-13 -2.06057e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1872 1873 4.52951 -0.257914 -0.206255 -0.00272989 0.0908209 -0.0869698 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1823 1873 1.15339e-11 -3.05972 -0.0937068 0.0612327 2.43805e-13 -2.06057e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1873 1874 4.5242 -0.257936 -0.205772 -0.0027303 0.0907145 -0.0870808 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1824 1874 1.15223e-11 -3.05972 -0.0937068 0.0612327 2.43805e-13 -2.06501e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1874 1875 4.51888 -0.257956 -0.20529 -0.00273068 0.0906079 -0.0871918 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1825 1875 1.15085e-11 -3.05972 -0.0937068 0.0612327 2.43361e-13 -2.06946e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1875 1876 4.51356 -0.257976 -0.204808 -0.00273104 0.0905012 -0.0873025 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1826 1876 1.14948e-11 -3.05972 -0.0937068 0.0612327 2.43361e-13 -2.06946e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1876 1877 4.50824 -0.257994 -0.204325 -0.00273138 0.0903943 -0.0874132 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1827 1877 1.14824e-11 -3.05972 -0.0937068 0.0612327 2.42917e-13 -2.0739e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1877 1878 4.5029 -0.258011 -0.203843 -0.00273169 0.0902874 -0.0875237 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1828 1878 1.14699e-11 -3.05972 -0.0937068 0.0612327 2.42917e-13 -2.07834e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1878 1879 4.49756 -0.258027 -0.20336 -0.00273198 0.0901802 -0.0876341 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1829 1879 1.14557e-11 -3.05972 -0.0937068 0.0612327 2.42473e-13 -2.07834e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1879 1880 4.49221 -0.258041 -0.202877 -0.00273225 0.090073 -0.0877443 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1830 1880 1.14433e-11 -3.05972 -0.0937068 0.0612327 2.42029e-13 -2.08278e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1880 1881 4.48686 -0.258054 -0.202395 -0.00273249 0.0899656 -0.0878544 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1831 1881 1.14255e-11 -3.05972 -0.0937068 0.0612327 2.42029e-13 -2.08722e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1881 1882 4.4815 -0.258067 -0.201912 -0.00273271 0.0898581 -0.0879644 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1832 1882 1.14184e-11 -3.05972 -0.0937068 0.0612327 2.41585e-13 -2.08722e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1882 1883 4.47613 -0.258078 -0.201429 -0.00273291 0.0897504 -0.0880743 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1833 1883 1.14007e-11 -3.05972 -0.0937068 0.0612327 2.41585e-13 -2.09166e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1883 1884 4.47076 -0.258088 -0.200947 -0.00273308 0.0896426 -0.088184 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1834 1884 1.13847e-11 -3.05972 -0.0937068 0.0612327 2.4114e-13 -2.0961e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1884 1885 4.46538 -0.258096 -0.200464 -0.00273322 0.0895347 -0.0882936 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1835 1885 1.13722e-11 -3.05972 -0.0937068 0.0612327 2.4114e-13 -2.0961e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1885 1886 4.45999 -0.258104 -0.199981 -0.00273335 0.0894267 -0.088403 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1836 1886 1.1358e-11 -3.05972 -0.0937068 0.0612327 2.40696e-13 -2.10054e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1886 1887 4.45459 -0.25811 -0.199498 -0.00273345 0.0893185 -0.0885123 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1837 1887 1.13438e-11 -3.05972 -0.0937068 0.0612327 2.40252e-13 -2.10498e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1887 1888 4.44919 -0.258115 -0.199015 -0.00273352 0.0892101 -0.0886215 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1838 1888 1.13305e-11 -3.05972 -0.0937068 0.0612327 2.40252e-13 -2.10498e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1888 1889 4.44378 -0.258119 -0.198533 -0.00273358 0.0891017 -0.0887306 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1839 1889 1.13189e-11 -3.05972 -0.0937068 0.0612327 2.39808e-13 -2.10942e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1889 1890 4.43837 -0.258122 -0.19805 -0.00273361 0.0889931 -0.0888395 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1840 1890 1.1303e-11 -3.05972 -0.0937068 0.0612327 2.39808e-13 -2.11386e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1890 1891 4.43295 -0.258123 -0.197567 -0.00273361 0.0888844 -0.0889482 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1841 1891 1.12941e-11 -3.05972 -0.0937068 0.0612327 2.39364e-13 -2.11386e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1891 1892 4.42752 -0.258124 -0.197084 -0.00273359 0.0887755 -0.0890569 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1842 1892 1.12763e-11 -3.05972 -0.0937068 0.0612327 2.39364e-13 -2.11831e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1892 1893 4.42209 -0.258123 -0.196601 -0.00273355 0.0886665 -0.0891654 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1843 1893 1.12621e-11 -3.05972 -0.0937068 0.0612327 2.3892e-13 -2.12275e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1893 1894 4.41664 -0.258121 -0.196118 -0.00273348 0.0885574 -0.0892738 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1844 1894 1.12443e-11 -3.05972 -0.0937068 0.0612327 2.38476e-13 -2.12275e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1894 1895 4.4112 -0.258118 -0.195636 -0.00273339 0.0884482 -0.089382 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1845 1895 1.12372e-11 -3.05972 -0.0937068 0.0612327 2.38476e-13 -2.12719e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1895 1896 4.40574 -0.258113 -0.195153 -0.00273328 0.0883388 -0.0894901 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1846 1896 1.12177e-11 -3.05972 -0.0937068 0.0612327 2.38032e-13 -2.13163e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1896 1897 4.40028 -0.258108 -0.19467 -0.00273314 0.0882293 -0.0895981 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1847 1897 1.12035e-11 -3.05972 -0.0937068 0.0612327 2.38032e-13 -2.13163e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1897 1898 4.39481 -0.258101 -0.194187 -0.00273298 0.0881196 -0.0897059 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1848 1898 1.1191e-11 -3.05972 -0.0937068 0.0612327 2.37588e-13 -2.13607e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1898 1899 4.38934 -0.258093 -0.193704 -0.00273279 0.0880099 -0.0898136 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1849 1899 1.11795e-11 -3.05972 -0.0937068 0.0612327 2.37144e-13 -2.14051e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1899 1900 4.38386 -0.258084 -0.193222 -0.00273259 0.0878999 -0.0899211 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1850 1900 1.11639e-11 -3.05972 -0.0937068 0.0612327 2.37144e-13 -2.14051e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1900 1901 4.37837 -0.258074 -0.192739 -0.00273235 0.0877899 -0.0900286 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1851 1901 1.11502e-11 -3.05972 -0.0937068 0.0612327 2.367e-13 -2.14495e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1901 1902 4.37288 -0.258062 -0.192256 -0.0027321 0.0876797 -0.0901359 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1852 1902 1.11342e-11 -3.05972 -0.0937068 0.0612327 2.367e-13 -2.14939e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1902 1903 4.36738 -0.25805 -0.191774 -0.00273182 0.0875694 -0.090243 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1853 1903 1.11218e-11 -3.05972 -0.0937068 0.0612327 2.36255e-13 -2.14939e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1903 1904 4.36187 -0.258036 -0.191291 -0.00273151 0.087459 -0.09035 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1854 1904 1.11058e-11 -3.05972 -0.0937068 0.0612327 2.36255e-13 -2.15383e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1904 1905 4.35636 -0.258021 -0.190808 -0.00273119 0.0873484 -0.0904569 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1855 1905 1.10951e-11 -3.05972 -0.0937068 0.0612327 2.35811e-13 -2.15827e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1905 1906 4.35084 -0.258005 -0.190326 -0.00273084 0.0872378 -0.0905636 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1856 1906 1.10809e-11 -3.05972 -0.0937068 0.0612327 2.35367e-13 -2.15827e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1906 1907 4.34531 -0.257988 -0.189843 -0.00273046 0.0871269 -0.0906702 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1857 1907 1.10632e-11 -3.05972 -0.0937068 0.0612327 2.35367e-13 -2.16271e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1907 1908 4.33978 -0.257969 -0.189361 -0.00273006 0.087016 -0.0907767 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1858 1908 1.10507e-11 -3.05972 -0.0937068 0.0612327 2.34923e-13 -2.16716e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1908 1909 4.33424 -0.257949 -0.188878 -0.00272964 0.0869049 -0.090883 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1859 1909 1.10401e-11 -3.05972 -0.0937068 0.0612327 2.34479e-13 -2.16716e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1909 1910 4.32869 -0.257928 -0.188396 -0.00272919 0.0867937 -0.0909892 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1860 1910 1.10205e-11 -3.05972 -0.0937068 0.0612327 2.34479e-13 -2.1716e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1910 1911 4.32314 -0.257906 -0.187914 -0.00272872 0.0866823 -0.0910953 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1861 1911 1.1009e-11 -3.05972 -0.0937068 0.0612327 2.34035e-13 -2.17604e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1911 1912 4.31758 -0.257883 -0.187431 -0.00272823 0.0865709 -0.0912012 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1862 1912 1.09948e-11 -3.05972 -0.0937068 0.0612327 2.34035e-13 -2.17604e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1912 1913 4.31201 -0.257859 -0.186949 -0.00272771 0.0864593 -0.0913069 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1863 1913 1.09805e-11 -3.05972 -0.0937068 0.0612327 2.33591e-13 -2.18048e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1913 1914 4.30644 -0.257833 -0.186467 -0.00272717 0.0863475 -0.0914126 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1864 1914 1.09663e-11 -3.05972 -0.0937068 0.0612327 2.33147e-13 -2.18048e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1914 1915 4.30086 -0.257806 -0.185985 -0.00272661 0.0862357 -0.0915181 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1865 1915 1.0953e-11 -3.05972 -0.0937068 0.0612327 2.33147e-13 -2.18492e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1915 1916 4.29528 -0.257778 -0.185503 -0.00272602 0.0861237 -0.0916234 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1866 1916 1.09353e-11 -3.05972 -0.0937068 0.0612327 2.32703e-13 -2.18936e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1916 1917 4.28969 -0.257749 -0.185021 -0.00272541 0.0860116 -0.0917287 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1867 1917 1.09228e-11 -3.05972 -0.0937068 0.0612327 2.32703e-13 -2.18936e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1917 1918 4.28409 -0.257719 -0.184539 -0.00272477 0.0858993 -0.0918337 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1868 1918 1.09139e-11 -3.05972 -0.0937068 0.0612327 2.32259e-13 -2.1938e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1918 1919 4.27849 -0.257687 -0.184057 -0.00272411 0.085787 -0.0919387 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1869 1919 1.08962e-11 -3.05972 -0.0937068 0.0612327 2.31815e-13 -2.19824e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1919 1920 4.27287 -0.257654 -0.183575 -0.00272343 0.0856745 -0.0920435 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1870 1920 1.08749e-11 -3.05972 -0.0937068 0.0612327 2.31815e-13 -2.19824e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1920 1921 4.26726 -0.257621 -0.183094 -0.00272272 0.0855618 -0.0921481 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1871 1921 1.08678e-11 -3.05972 -0.0937068 0.0612327 2.3137e-13 -2.20268e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1921 1922 4.26163 -0.257585 -0.182612 -0.00272199 0.0854491 -0.0922527 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1872 1922 1.08535e-11 -3.05972 -0.0937068 0.0612327 2.30926e-13 -2.20268e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1922 1923 4.256 -0.257549 -0.182131 -0.00272124 0.0853362 -0.0923571 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1873 1923 1.08411e-11 -3.05972 -0.0937068 0.0612327 2.30926e-13 -2.20712e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1923 1924 4.25037 -0.257512 -0.181649 -0.00272046 0.0852232 -0.0924613 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1874 1924 1.08225e-11 -3.05972 -0.0937068 0.0612327 2.30482e-13 -2.21156e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1924 1925 4.24472 -0.257473 -0.181168 -0.00271966 0.0851101 -0.0925654 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1875 1925 1.08089e-11 -3.05972 -0.0937068 0.0612327 2.30482e-13 -2.21156e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1925 1926 4.23908 -0.257433 -0.180687 -0.00271884 0.0849968 -0.0926694 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1876 1926 1.07949e-11 -3.05972 -0.0937068 0.0612327 2.30038e-13 -2.21601e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1926 1927 4.23342 -0.257392 -0.180206 -0.00271799 0.0848834 -0.0927732 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1877 1927 1.07789e-11 -3.05972 -0.0937068 0.0612327 2.30038e-13 -2.22045e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1927 1928 4.22776 -0.25735 -0.179725 -0.00271712 0.0847699 -0.0928769 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1878 1928 1.07647e-11 -3.05972 -0.0937068 0.0612327 2.29594e-13 -2.22045e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1928 1929 4.22209 -0.257307 -0.179244 -0.00271622 0.0846563 -0.0929804 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1879 1929 1.07487e-11 -3.05972 -0.0937068 0.0612327 2.2915e-13 -2.22489e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1929 1930 4.21642 -0.257263 -0.178763 -0.0027153 0.0845425 -0.0930838 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1880 1930 1.07363e-11 -3.05972 -0.0937068 0.0612327 2.2915e-13 -2.22933e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1930 1931 4.21074 -0.257217 -0.178282 -0.00271436 0.0844286 -0.0931871 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1881 1931 1.07256e-11 -3.05972 -0.0937068 0.0612327 2.28706e-13 -2.22933e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1931 1932 4.20505 -0.25717 -0.177802 -0.00271339 0.0843146 -0.0932902 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1882 1932 1.07043e-11 -3.05972 -0.0937068 0.0612327 2.28262e-13 -2.23377e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1932 1933 4.19936 -0.257122 -0.177321 -0.0027124 0.0842004 -0.0933932 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1883 1933 1.06972e-11 -3.05972 -0.0937068 0.0612327 2.28262e-13 -2.23821e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1933 1934 4.19366 -0.257073 -0.176841 -0.00271139 0.0840862 -0.093496 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1884 1934 1.06777e-11 -3.05972 -0.0937068 0.0612327 2.27818e-13 -2.23821e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1934 1935 4.18795 -0.257022 -0.176361 -0.00271035 0.0839718 -0.0935987 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1885 1935 1.06635e-11 -3.05972 -0.0937068 0.0612327 2.27818e-13 -2.24265e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1935 1936 4.18224 -0.256971 -0.175881 -0.00270929 0.0838572 -0.0937013 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1886 1936 1.06484e-11 -3.05972 -0.0937068 0.0612327 2.27374e-13 -2.24265e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1936 1937 4.17652 -0.256918 -0.175401 -0.0027082 0.0837426 -0.0938037 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1887 1937 1.0635e-11 -3.05972 -0.0937068 0.0612327 2.2693e-13 -2.24709e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1937 1938 4.17079 -0.256864 -0.174921 -0.0027071 0.0836278 -0.093906 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1888 1938 1.06204e-11 -3.05972 -0.0937068 0.0612327 2.2693e-13 -2.25153e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1938 1939 4.16506 -0.256809 -0.174441 -0.00270597 0.0835129 -0.0940081 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1889 1939 1.0604e-11 -3.05972 -0.0937068 0.0612327 2.26485e-13 -2.25153e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1939 1940 4.15933 -0.256753 -0.173962 -0.00270481 0.0833979 -0.0941101 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1890 1940 1.05924e-11 -3.05972 -0.0937068 0.0612327 2.26485e-13 -2.25597e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1940 1941 4.15358 -0.256695 -0.173482 -0.00270363 0.0832828 -0.0942119 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1891 1941 1.05747e-11 -3.05972 -0.0937068 0.0612327 2.26041e-13 -2.25597e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1941 1942 4.14783 -0.256637 -0.173003 -0.00270243 0.0831675 -0.0943136 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1892 1942 1.05587e-11 -3.05972 -0.0937068 0.0612327 2.25597e-13 -2.26041e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1942 1943 4.14208 -0.256577 -0.172524 -0.0027012 0.0830521 -0.0944152 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1893 1943 1.05409e-11 -3.05972 -0.0937068 0.0612327 2.25597e-13 -2.26485e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1943 1944 4.13632 -0.256516 -0.172045 -0.00269995 0.0829366 -0.0945166 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1894 1944 1.05373e-11 -3.05972 -0.0937068 0.0612327 2.25153e-13 -2.26485e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1944 1945 4.13055 -0.256454 -0.171566 -0.00269868 0.082821 -0.0946179 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1895 1945 1.05143e-11 -3.05972 -0.0937068 0.0612327 2.24709e-13 -2.2693e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1945 1946 4.12477 -0.256391 -0.171088 -0.00269739 0.0827052 -0.094719 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1896 1946 1.05054e-11 -3.05972 -0.0937068 0.0612327 2.24709e-13 -2.27374e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1946 1947 4.11899 -0.256326 -0.170609 -0.00269607 0.0825893 -0.09482 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1897 1947 1.04894e-11 -3.05972 -0.0937068 0.0612327 2.24265e-13 -2.27374e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1947 1948 4.1132 -0.256261 -0.170131 -0.00269472 0.0824733 -0.0949209 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1898 1948 1.04716e-11 -3.05972 -0.0937068 0.0612327 2.23821e-13 -2.27818e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1948 1949 4.10741 -0.256194 -0.169652 -0.00269336 0.0823572 -0.0950216 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1899 1949 1.04583e-11 -3.05972 -0.0937068 0.0612327 2.23821e-13 -2.27818e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1949 1950 4.10161 -0.256126 -0.169174 -0.00269197 0.0822409 -0.0951221 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1900 1950 1.04437e-11 -3.05972 -0.0937068 0.0612327 2.23377e-13 -2.28262e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1950 1951 4.09581 -0.256057 -0.168697 -0.00269055 0.0821245 -0.0952226 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1901 1951 1.0429e-11 -3.05972 -0.0937068 0.0612327 2.23377e-13 -2.28706e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1951 1952 4.09 -0.255986 -0.168219 -0.00268912 0.082008 -0.0953228 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1902 1952 1.04157e-11 -3.05972 -0.0937068 0.0612327 2.22933e-13 -2.28706e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1952 1953 4.08418 -0.255915 -0.167741 -0.00268766 0.0818914 -0.095423 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1903 1953 1.0397e-11 -3.05972 -0.0937068 0.0612327 2.22933e-13 -2.2915e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1953 1954 4.07835 -0.255842 -0.167264 -0.00268617 0.0817747 -0.0955229 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1904 1954 1.03881e-11 -3.05972 -0.0937068 0.0612327 2.22489e-13 -2.29594e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1954 1955 4.07252 -0.255768 -0.166787 -0.00268466 0.0816578 -0.0956228 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1905 1955 1.03668e-11 -3.05972 -0.0937068 0.0612327 2.22045e-13 -2.29594e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1955 1956 4.06669 -0.255693 -0.16631 -0.00268313 0.0815408 -0.0957225 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1906 1956 1.03562e-11 -3.05972 -0.0937068 0.0612327 2.22045e-13 -2.30038e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1956 1957 4.06085 -0.255617 -0.165833 -0.00268158 0.0814237 -0.095822 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1907 1957 1.03419e-11 -3.05972 -0.0937068 0.0612327 2.21601e-13 -2.30038e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1957 1958 4.055 -0.25554 -0.165356 -0.00268 0.0813065 -0.0959214 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1908 1958 1.03242e-11 -3.05972 -0.0937068 0.0612327 2.21156e-13 -2.30482e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1958 1959 4.04914 -0.255461 -0.16488 -0.0026784 0.0811891 -0.0960207 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1909 1959 1.031e-11 -3.05972 -0.0937068 0.0612327 2.21156e-13 -2.30926e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1959 1960 4.04328 -0.255382 -0.164404 -0.00267678 0.0810716 -0.0961198 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1910 1960 1.02958e-11 -3.05972 -0.0937068 0.0612327 2.20712e-13 -2.30926e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1960 1961 4.03742 -0.255301 -0.163928 -0.00267513 0.0809541 -0.0962188 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1911 1961 1.02807e-11 -3.05972 -0.0937068 0.0612327 2.20268e-13 -2.3137e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1961 1962 4.03154 -0.255219 -0.163452 -0.00267346 0.0808363 -0.0963176 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1912 1962 1.02642e-11 -3.05972 -0.0937068 0.0612327 2.20268e-13 -2.3137e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1962 1963 4.02567 -0.255136 -0.162976 -0.00267176 0.0807185 -0.0964163 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1913 1963 1.025e-11 -3.05972 -0.0937068 0.0612327 2.19824e-13 -2.31815e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1963 1964 4.01978 -0.255051 -0.162501 -0.00267005 0.0806006 -0.0965148 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1914 1964 1.02354e-11 -3.05972 -0.0937068 0.0612327 2.1938e-13 -2.32259e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1964 1965 4.01389 -0.254966 -0.162026 -0.0026683 0.0804825 -0.0966132 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1915 1965 1.02212e-11 -3.05972 -0.0937068 0.0612327 2.1938e-13 -2.32259e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1965 1966 4.00799 -0.254879 -0.161551 -0.00266654 0.0803643 -0.0967115 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1916 1966 1.02069e-11 -3.05972 -0.0937068 0.0612327 2.18936e-13 -2.32703e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1966 1967 4.00209 -0.254791 -0.161076 -0.00266475 0.080246 -0.0968095 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1917 1967 1.01874e-11 -3.05972 -0.0937068 0.0612327 2.18492e-13 -2.32703e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1967 1968 3.99618 -0.254702 -0.160601 -0.00266294 0.0801275 -0.0969075 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1918 1968 1.0175e-11 -3.05972 -0.0937068 0.0612327 2.18492e-13 -2.33147e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1968 1969 3.99027 -0.254612 -0.160127 -0.00266111 0.080009 -0.0970053 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1919 1969 1.01625e-11 -3.05972 -0.0937068 0.0612327 2.18048e-13 -2.33591e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1969 1970 3.98435 -0.254521 -0.159653 -0.00265925 0.0798903 -0.097103 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1920 1970 1.0143e-11 -3.05972 -0.0937068 0.0612327 2.18048e-13 -2.33591e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1970 1971 3.97842 -0.254428 -0.159179 -0.00265737 0.0797715 -0.0972005 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1921 1971 1.01306e-11 -3.05972 -0.0937068 0.0612327 2.17604e-13 -2.34035e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1971 1972 3.97249 -0.254335 -0.158705 -0.00265547 0.0796526 -0.0972978 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1922 1972 1.01128e-11 -3.05972 -0.0937068 0.0612327 2.1716e-13 -2.34479e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1972 1973 3.96655 -0.25424 -0.158232 -0.00265354 0.0795336 -0.0973951 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1923 1973 1.00959e-11 -3.05972 -0.0937068 0.0612327 2.1716e-13 -2.34479e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1973 1974 3.96061 -0.254144 -0.157759 -0.00265159 0.0794144 -0.0974921 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1924 1974 1.00857e-11 -3.05972 -0.0937068 0.0612327 2.16716e-13 -2.34923e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1974 1975 3.95466 -0.254047 -0.157286 -0.00264962 0.0792952 -0.0975891 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1925 1975 1.00687e-11 -3.05972 -0.0937068 0.0612327 2.16271e-13 -2.34923e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1975 1976 3.9487 -0.253949 -0.156813 -0.00264762 0.0791758 -0.0976858 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1926 1976 1.00528e-11 -3.05972 -0.0937068 0.0612327 2.16271e-13 -2.35367e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1976 1977 3.94274 -0.253849 -0.156341 -0.0026456 0.0790563 -0.0977825 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1927 1977 1.00409e-11 -3.05972 -0.0937068 0.0612327 2.15827e-13 -2.35367e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1977 1978 3.93677 -0.253749 -0.155868 -0.00264356 0.0789367 -0.0978789 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1928 1978 1.0024e-11 -3.05972 -0.0937068 0.0612327 2.15383e-13 -2.35811e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1978 1979 3.93079 -0.253647 -0.155396 -0.00264149 0.0788169 -0.0979753 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1929 1979 1.00098e-11 -3.05972 -0.0937068 0.0612327 2.15383e-13 -2.36255e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1979 1980 3.92481 -0.253544 -0.154925 -0.0026394 0.0786971 -0.0980715 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1930 1980 9.98845e-12 -3.05972 -0.0937068 0.0612327 2.14939e-13 -2.36255e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1980 1981 3.91883 -0.25344 -0.154453 -0.00263729 0.0785771 -0.0981675 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1931 1981 9.9778e-12 -3.05972 -0.0937068 0.0612327 2.14939e-13 -2.367e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1981 1982 3.91284 -0.253335 -0.153982 -0.00263515 0.078457 -0.0982634 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1932 1982 9.96359e-12 -3.05972 -0.0937068 0.0612327 2.14495e-13 -2.367e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1982 1983 3.90684 -0.253228 -0.153511 -0.00263299 0.0783368 -0.0983591 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1933 1983 9.94937e-12 -3.05972 -0.0937068 0.0612327 2.14051e-13 -2.37144e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1983 1984 3.90084 -0.253121 -0.15304 -0.00263081 0.0782165 -0.0984547 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1934 1984 9.93161e-12 -3.05972 -0.0937068 0.0612327 2.14051e-13 -2.37588e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1984 1985 3.89483 -0.253012 -0.15257 -0.00262861 0.0780961 -0.0985502 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1935 1985 9.91562e-12 -3.05972 -0.0937068 0.0612327 2.13607e-13 -2.37588e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1985 1986 3.88881 -0.252902 -0.152099 -0.00262638 0.0779755 -0.0986455 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1936 1986 9.90141e-12 -3.05972 -0.0937068 0.0612327 2.13163e-13 -2.38032e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1986 1987 3.88279 -0.252791 -0.15163 -0.00262413 0.0778549 -0.0987406 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1937 1987 9.8852e-12 -3.05972 -0.0937068 0.0612327 2.13163e-13 -2.38032e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1987 1988 3.87676 -0.252679 -0.15116 -0.00262186 0.0777341 -0.0988356 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1938 1988 9.86988e-12 -3.05972 -0.0937068 0.0612327 2.12719e-13 -2.38476e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1988 1989 3.87073 -0.252566 -0.150691 -0.00261956 0.0776132 -0.0989305 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1939 1989 9.85523e-12 -3.05972 -0.0937068 0.0612327 2.12275e-13 -2.3892e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1989 1990 3.86469 -0.252452 -0.150221 -0.00261724 0.0774922 -0.0990252 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1940 1990 9.84102e-12 -3.05972 -0.0937068 0.0612327 2.12275e-13 -2.3892e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1990 1991 3.85865 -0.252336 -0.149753 -0.0026149 0.077371 -0.0991197 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1941 1991 9.82503e-12 -3.05972 -0.0937068 0.0612327 2.11831e-13 -2.39364e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1991 1992 3.8526 -0.252219 -0.149284 -0.00261253 0.0772498 -0.0992141 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1942 1992 9.81082e-12 -3.05972 -0.0937068 0.0612327 2.11386e-13 -2.39364e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1992 1993 3.84654 -0.252101 -0.148816 -0.00261014 0.0771284 -0.0993084 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1943 1993 9.79838e-12 -3.05972 -0.0937068 0.0612327 2.11386e-13 -2.39808e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1993 1994 3.84048 -0.251982 -0.148348 -0.00260773 0.0770069 -0.0994025 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1944 1994 9.77529e-12 -3.05972 -0.0937068 0.0612327 2.10942e-13 -2.39808e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1994 1995 3.83441 -0.251862 -0.14788 -0.0026053 0.0768853 -0.0994964 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1945 1995 9.76108e-12 -3.05972 -0.0937068 0.0612327 2.10498e-13 -2.40252e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1995 1996 3.82834 -0.251741 -0.147413 -0.00260284 0.0767636 -0.0995902 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1946 1996 9.74687e-12 -3.05972 -0.0937068 0.0612327 2.10498e-13 -2.40696e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1996 1997 3.82226 -0.251619 -0.146946 -0.00260036 0.0766418 -0.0996839 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1947 1997 9.73266e-12 -3.05972 -0.0937068 0.0612327 2.10054e-13 -2.40696e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1997 1998 3.81618 -0.251495 -0.146479 -0.00259785 0.0765199 -0.0997774 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1948 1998 9.71667e-12 -3.05972 -0.0937068 0.0612327 2.0961e-13 -2.4114e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1998 1999 3.81009 -0.25137 -0.146013 -0.00259533 0.0763978 -0.0998707 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1949 1999 9.6998e-12 -3.05972 -0.0937068 0.0612327 2.0961e-13 -2.4114e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1999 2000 3.80399 -0.251244 -0.145547 -0.00259278 0.0762757 -0.0999639 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1950 2000 9.68433e-12 -3.05972 -0.0937068 0.0612327 2.09166e-13 -2.41585e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2000 2001 3.79789 -0.251117 -0.145081 -0.00259021 0.0761534 -0.100057 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1951 2001 9.66782e-12 -3.05972 -0.0937068 0.0612327 2.08722e-13 -2.41585e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2001 2002 3.79178 -0.250989 -0.144615 -0.00258761 0.076031 -0.10015 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1952 2002 9.65272e-12 -3.05972 -0.0937068 0.0612327 2.08722e-13 -2.42029e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2002 2003 3.78567 -0.25086 -0.14415 -0.00258499 0.0759085 -0.100243 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1953 2003 9.63674e-12 -3.05972 -0.0937068 0.0612327 2.08278e-13 -2.42473e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2003 2004 3.77955 -0.25073 -0.143685 -0.00258235 0.0757859 -0.100335 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1954 2004 9.62252e-12 -3.05972 -0.0937068 0.0612327 2.07834e-13 -2.42473e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2004 2005 3.77343 -0.250598 -0.143221 -0.00257969 0.0756632 -0.100428 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1955 2005 9.60476e-12 -3.05972 -0.0937068 0.0612327 2.0739e-13 -2.42917e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2005 2006 3.7673 -0.250465 -0.142756 -0.00257701 0.0755403 -0.10052 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1956 2006 9.5941e-12 -3.05972 -0.0937068 0.0612327 2.0739e-13 -2.42917e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2006 2007 3.76116 -0.250331 -0.142292 -0.0025743 0.0754174 -0.100612 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1957 2007 9.57634e-12 -3.05972 -0.0937068 0.0612327 2.06946e-13 -2.43361e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2007 2008 3.75502 -0.250196 -0.141829 -0.00257157 0.0752943 -0.100704 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1958 2008 9.5568e-12 -3.05972 -0.0937068 0.0612327 2.06946e-13 -2.43361e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2008 2009 3.74887 -0.25006 -0.141366 -0.00256881 0.0751712 -0.100796 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1959 2009 9.54081e-12 -3.05972 -0.0937068 0.0612327 2.06501e-13 -2.43805e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2009 2010 3.74272 -0.249923 -0.140903 -0.00256604 0.0750479 -0.100888 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1960 2010 9.5266e-12 -3.05972 -0.0937068 0.0612327 2.06057e-13 -2.44249e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2010 2011 3.73656 -0.249785 -0.14044 -0.00256324 0.0749245 -0.100979 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1961 2011 9.51239e-12 -3.05972 -0.0937068 0.0612327 2.06057e-13 -2.44249e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2011 2012 3.7304 -0.249645 -0.139978 -0.00256041 0.074801 -0.101071 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1962 2012 9.4964e-12 -3.05972 -0.0937068 0.0612327 2.05613e-13 -2.44693e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2012 2013 3.72423 -0.249504 -0.139516 -0.00255757 0.0746773 -0.101162 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1963 2013 9.48108e-12 -3.05972 -0.0937068 0.0612327 2.05169e-13 -2.44693e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2013 2014 3.71805 -0.249363 -0.139054 -0.0025547 0.0745536 -0.101253 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1964 2014 9.46532e-12 -3.05972 -0.0937068 0.0612327 2.04725e-13 -2.45137e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2014 2015 3.71187 -0.24922 -0.138593 -0.00255181 0.0744298 -0.101344 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1965 2015 9.45022e-12 -3.05972 -0.0937068 0.0612327 2.04725e-13 -2.45137e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2015 2016 3.70569 -0.249076 -0.138132 -0.0025489 0.0743058 -0.101435 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1966 2016 9.43423e-12 -3.05972 -0.0937068 0.0612327 2.04281e-13 -2.45581e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2016 2017 3.69949 -0.248931 -0.137672 -0.00254597 0.0741817 -0.101525 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1967 2017 9.41824e-12 -3.05972 -0.0937068 0.0612327 2.04281e-13 -2.46025e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2017 2018 3.6933 -0.248784 -0.137212 -0.00254301 0.0740576 -0.101616 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1968 2018 9.40226e-12 -3.05972 -0.0937068 0.0612327 2.03837e-13 -2.46025e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2018 2019 3.68709 -0.248637 -0.136752 -0.00254003 0.0739333 -0.101706 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1969 2019 9.38449e-12 -3.05972 -0.0937068 0.0612327 2.03393e-13 -2.4647e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2019 2020 3.68089 -0.248488 -0.136292 -0.00253703 0.0738089 -0.101796 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1970 2020 9.37206e-12 -3.05972 -0.0937068 0.0612327 2.02949e-13 -2.4647e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2020 2021 3.67467 -0.248339 -0.135833 -0.002534 0.0736844 -0.101886 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1971 2021 9.3543e-12 -3.05972 -0.0937068 0.0612327 2.02949e-13 -2.46914e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2021 2022 3.66845 -0.248188 -0.135375 -0.00253095 0.0735598 -0.101976 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1972 2022 9.34008e-12 -3.05972 -0.0937068 0.0612327 2.02505e-13 -2.46914e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2022 2023 3.66223 -0.248036 -0.134916 -0.00252788 0.073435 -0.102066 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1973 2023 9.32321e-12 -3.05972 -0.0937068 0.0612327 2.02061e-13 -2.47358e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2023 2024 3.656 -0.247883 -0.134458 -0.00252479 0.0733102 -0.102155 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1974 2024 9.30589e-12 -3.05972 -0.0937068 0.0612327 2.02061e-13 -2.47802e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2024 2025 3.64976 -0.247729 -0.134001 -0.00252168 0.0731853 -0.102245 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1975 2025 9.29086e-12 -3.05972 -0.0937068 0.0612327 2.01617e-13 -2.47802e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2025 2026 3.64352 -0.247573 -0.133544 -0.00251854 0.0730602 -0.102334 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1976 2026 9.27525e-12 -3.05972 -0.0937068 0.0612327 2.01172e-13 -2.48246e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2026 2027 3.63727 -0.247417 -0.133087 -0.00251538 0.0729351 -0.102423 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1977 2027 9.25748e-12 -3.05972 -0.0937068 0.0612327 2.01172e-13 -2.48246e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2027 2028 3.63102 -0.24726 -0.13263 -0.0025122 0.0728098 -0.102512 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1978 2028 9.24061e-12 -3.05972 -0.0937068 0.0612327 2.00728e-13 -2.4869e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2028 2029 3.62476 -0.247101 -0.132174 -0.002509 0.0726844 -0.102601 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1979 2029 9.2264e-12 -3.05972 -0.0937068 0.0612327 2.00284e-13 -2.4869e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2029 2030 3.6185 -0.246941 -0.131719 -0.00250577 0.0725589 -0.102689 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1980 2030 9.21752e-12 -3.05972 -0.0937068 0.0612327 2.00284e-13 -2.49134e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2030 2031 3.61223 -0.24678 -0.131264 -0.00250252 0.0724333 -0.102778 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1981 2031 9.19265e-12 -3.05972 -0.0937068 0.0612327 1.9984e-13 -2.49134e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2031 2032 3.60596 -0.246618 -0.130809 -0.00249925 0.0723076 -0.102866 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1982 2032 9.17666e-12 -3.05972 -0.0937068 0.0612327 1.99396e-13 -2.49578e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2032 2033 3.59968 -0.246455 -0.130354 -0.00249596 0.0721818 -0.102954 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1983 2033 9.16067e-12 -3.05972 -0.0937068 0.0612327 1.98952e-13 -2.49578e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2033 2034 3.59339 -0.246291 -0.1299 -0.00249264 0.0720559 -0.103042 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1984 2034 9.14646e-12 -3.05972 -0.0937068 0.0612327 1.98952e-13 -2.50022e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2034 2035 3.5871 -0.246126 -0.129447 -0.0024893 0.0719299 -0.10313 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1985 2035 9.13225e-12 -3.05972 -0.0937068 0.0612327 1.98508e-13 -2.50466e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2035 2036 3.58081 -0.245959 -0.128993 -0.00248594 0.0718038 -0.103218 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1986 2036 9.11538e-12 -3.05972 -0.0937068 0.0612327 1.98064e-13 -2.50466e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2036 2037 3.57451 -0.245792 -0.12854 -0.00248256 0.0716775 -0.103305 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1987 2037 9.09872e-12 -3.05972 -0.0937068 0.0612327 1.98064e-13 -2.5091e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2037 2038 3.5682 -0.245623 -0.128088 -0.00247916 0.0715512 -0.103393 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1988 2038 9.08296e-12 -3.05972 -0.0937068 0.0612327 1.9762e-13 -2.5091e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2038 2039 3.56189 -0.245453 -0.127636 -0.00247573 0.0714247 -0.10348 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1989 2039 9.06653e-12 -3.05972 -0.0937068 0.0612327 1.97176e-13 -2.51354e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2039 2040 3.55557 -0.245282 -0.127184 -0.00247228 0.0712982 -0.103567 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1990 2040 9.04876e-12 -3.05972 -0.0937068 0.0612327 1.97176e-13 -2.51354e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2040 2041 3.54925 -0.245111 -0.126733 -0.00246881 0.0711715 -0.103654 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1991 2041 9.03277e-12 -3.05972 -0.0937068 0.0612327 1.96732e-13 -2.51799e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2041 2042 3.54292 -0.244937 -0.126282 -0.00246532 0.0710448 -0.103741 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1992 2042 9.02212e-12 -3.05972 -0.0937068 0.0612327 1.96287e-13 -2.52243e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2042 2043 3.53659 -0.244763 -0.125832 -0.0024618 0.0709179 -0.103827 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1993 2043 9.00258e-12 -3.05972 -0.0937068 0.0612327 1.96287e-13 -2.52243e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2043 2044 3.53025 -0.244588 -0.125382 -0.00245827 0.0707909 -0.103914 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1994 2044 8.98659e-12 -3.05972 -0.0937068 0.0612327 1.95843e-13 -2.52243e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2044 2045 3.52391 -0.244412 -0.124933 -0.00245471 0.0706638 -0.104 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1995 2045 8.96883e-12 -3.05972 -0.0937068 0.0612327 1.95399e-13 -2.52687e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2045 2046 3.51756 -0.244234 -0.124484 -0.00245113 0.0705366 -0.104086 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1996 2046 8.95284e-12 -3.05972 -0.0937068 0.0612327 1.95399e-13 -2.53131e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2046 2047 3.51121 -0.244056 -0.124035 -0.00244753 0.0704094 -0.104172 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1997 2047 8.93685e-12 -3.05972 -0.0937068 0.0612327 1.94955e-13 -2.53131e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2047 2048 3.50485 -0.243876 -0.123587 -0.0024439 0.070282 -0.104258 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1998 2048 8.92264e-12 -3.05972 -0.0937068 0.0612327 1.94511e-13 -2.53575e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2048 2049 3.49848 -0.243695 -0.123139 -0.00244026 0.0701545 -0.104344 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 1999 2049 8.90443e-12 -3.05972 -0.0937068 0.0612327 1.94067e-13 -2.53575e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2049 2050 3.49211 -0.243513 -0.122692 -0.00243659 0.0700269 -0.104429 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2000 2050 8.88867e-12 -3.05972 -0.0937068 0.0612327 1.94067e-13 -2.54019e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2050 2051 3.48574 -0.24333 -0.122245 -0.0024329 0.0698991 -0.104515 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2001 2051 8.8729e-12 -3.05972 -0.0937068 0.0612327 1.93623e-13 -2.54019e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2051 2052 3.47936 -0.243146 -0.121799 -0.00242919 0.0697713 -0.1046 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2002 2052 8.85514e-12 -3.05972 -0.0937068 0.0612327 1.93179e-13 -2.54463e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2052 2053 3.47297 -0.242961 -0.121353 -0.00242545 0.0696434 -0.104685 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2003 2053 8.8427e-12 -3.05972 -0.0937068 0.0612327 1.93179e-13 -2.54907e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2053 2054 3.46658 -0.242775 -0.120907 -0.0024217 0.0695154 -0.10477 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2004 2054 8.82139e-12 -3.05972 -0.0937068 0.0612327 1.92735e-13 -2.54907e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2054 2055 3.46018 -0.242587 -0.120462 -0.00241792 0.0693873 -0.104854 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2005 2055 8.81073e-12 -3.05972 -0.0937068 0.0612327 1.92291e-13 -2.54907e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2055 2056 3.45378 -0.242399 -0.120018 -0.00241412 0.069259 -0.104939 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2006 2056 8.78586e-12 -3.05972 -0.0937068 0.0612327 1.92291e-13 -2.55351e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2056 2057 3.44738 -0.24221 -0.119574 -0.0024103 0.0691307 -0.105023 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2007 2057 8.7752e-12 -3.05972 -0.0937068 0.0612327 1.91847e-13 -2.55351e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2057 2058 3.44097 -0.242019 -0.11913 -0.00240646 0.0690023 -0.105108 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2008 2058 8.75922e-12 -3.05972 -0.0937068 0.0612327 1.91402e-13 -2.55795e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2058 2059 3.43455 -0.241827 -0.118687 -0.00240259 0.0688737 -0.105192 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2009 2059 8.745e-12 -3.05972 -0.0937068 0.0612327 1.90958e-13 -2.55795e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2059 2060 3.42813 -0.241634 -0.118244 -0.00239871 0.0687451 -0.105276 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2010 2060 8.72724e-12 -3.05972 -0.0937068 0.0612327 1.90958e-13 -2.56239e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2060 2061 3.4217 -0.241441 -0.117802 -0.0023948 0.0686164 -0.105359 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2011 2061 8.70859e-12 -3.05972 -0.0937068 0.0612327 1.90514e-13 -2.56684e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2061 2062 3.41527 -0.241246 -0.11736 -0.00239087 0.0684875 -0.105443 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2012 2062 8.69282e-12 -3.05972 -0.0937068 0.0612327 1.9007e-13 -2.56684e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2062 2063 3.40883 -0.24105 -0.116919 -0.00238692 0.0683586 -0.105526 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2013 2063 8.67595e-12 -3.05972 -0.0937068 0.0612327 1.9007e-13 -2.57128e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2063 2064 3.40239 -0.240853 -0.116478 -0.00238295 0.0682295 -0.10561 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2014 2064 8.66063e-12 -3.05972 -0.0937068 0.0612327 1.89626e-13 -2.57128e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2064 2065 3.39594 -0.240654 -0.116038 -0.00237895 0.0681004 -0.105693 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2015 2065 8.64286e-12 -3.05972 -0.0937068 0.0612327 1.89182e-13 -2.57572e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2065 2066 3.38949 -0.240455 -0.115598 -0.00237494 0.0679711 -0.105776 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2016 2066 8.62599e-12 -3.05972 -0.0937068 0.0612327 1.89182e-13 -2.57572e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2066 2067 3.38303 -0.240255 -0.115159 -0.0023709 0.0678418 -0.105859 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2017 2067 8.61178e-12 -3.05972 -0.0937068 0.0612327 1.88738e-13 -2.58016e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2067 2068 3.37657 -0.240053 -0.11472 -0.00236684 0.0677124 -0.105941 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2018 2068 8.59579e-12 -3.05972 -0.0937068 0.0612327 1.88294e-13 -2.58016e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2068 2069 3.3701 -0.239851 -0.114282 -0.00236276 0.0675828 -0.106024 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2019 2069 8.5798e-12 -3.05972 -0.0937068 0.0612327 1.8785e-13 -2.5846e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2069 2070 3.36363 -0.239647 -0.113844 -0.00235866 0.0674532 -0.106106 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2020 2070 8.56204e-12 -3.05972 -0.0937068 0.0612327 1.8785e-13 -2.5846e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2070 2071 3.35715 -0.239443 -0.113407 -0.00235454 0.0673234 -0.106188 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2021 2071 8.54783e-12 -3.05972 -0.0937068 0.0612327 1.87406e-13 -2.58904e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2071 2072 3.35067 -0.239237 -0.11297 -0.0023504 0.0671936 -0.10627 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2022 2072 8.52651e-12 -3.05972 -0.0937068 0.0612327 1.86962e-13 -2.58904e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2072 2073 3.34418 -0.23903 -0.112533 -0.00234623 0.0670636 -0.106352 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2023 2073 8.5123e-12 -3.05972 -0.0937068 0.0612327 1.86517e-13 -2.59348e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2073 2074 3.33769 -0.238822 -0.112098 -0.00234204 0.0669336 -0.106434 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2024 2074 8.49498e-12 -3.05972 -0.0937068 0.0612327 1.86517e-13 -2.59348e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2074 2075 3.33119 -0.238614 -0.111662 -0.00233784 0.0668034 -0.106516 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2025 2075 8.47816e-12 -3.05972 -0.0937068 0.0612327 1.86073e-13 -2.59792e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2075 2076 3.32469 -0.238404 -0.111227 -0.00233361 0.0666732 -0.106597 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2026 2076 8.46079e-12 -3.05972 -0.0937068 0.0612327 1.85629e-13 -2.59792e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2076 2077 3.31818 -0.238193 -0.110793 -0.00232936 0.0665428 -0.106678 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2027 2077 8.44569e-12 -3.05972 -0.0937068 0.0612327 1.85629e-13 -2.60236e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2077 2078 3.31166 -0.23798 -0.110359 -0.00232509 0.0664124 -0.106759 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2028 2078 8.43059e-12 -3.05972 -0.0937068 0.0612327 1.85185e-13 -2.60236e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2078 2079 3.30515 -0.237767 -0.109926 -0.00232079 0.0662818 -0.10684 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2029 2079 8.41105e-12 -3.05972 -0.0937068 0.0612327 1.84741e-13 -2.6068e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2079 2080 3.29862 -0.237553 -0.109493 -0.00231648 0.0661512 -0.106921 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2030 2080 8.39506e-12 -3.05972 -0.0937068 0.0612327 1.84741e-13 -2.6068e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2080 2081 3.2921 -0.237338 -0.109061 -0.00231214 0.0660204 -0.107002 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2031 2081 8.37908e-12 -3.05972 -0.0937068 0.0612327 1.84297e-13 -2.61124e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2081 2082 3.28556 -0.237121 -0.10863 -0.00230779 0.0658896 -0.107082 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2032 2082 8.35954e-12 -3.05972 -0.0937068 0.0612327 1.83853e-13 -2.61124e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2082 2083 3.27903 -0.236904 -0.108198 -0.00230341 0.0657587 -0.107162 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2033 2083 8.3471e-12 -3.05972 -0.0937068 0.0612327 1.83409e-13 -2.61569e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2083 2084 3.27248 -0.236686 -0.107768 -0.00229901 0.0656276 -0.107242 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2034 2084 8.32756e-12 -3.05972 -0.0937068 0.0612327 1.83409e-13 -2.62013e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2084 2085 3.26594 -0.236466 -0.107338 -0.00229459 0.0654965 -0.107322 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2035 2085 8.31157e-12 -3.05972 -0.0937068 0.0612327 1.82965e-13 -2.62013e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2085 2086 3.25938 -0.236246 -0.106908 -0.00229015 0.0653653 -0.107402 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2036 2086 8.2947e-12 -3.05972 -0.0937068 0.0612327 1.82521e-13 -2.62013e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2086 2087 3.25283 -0.236024 -0.106479 -0.00228569 0.0652339 -0.107482 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2037 2087 8.27849e-12 -3.05972 -0.0937068 0.0612327 1.82077e-13 -2.62457e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2087 2088 3.24626 -0.235801 -0.106051 -0.00228121 0.0651025 -0.107561 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2038 2088 8.26184e-12 -3.05972 -0.0937068 0.0612327 1.82077e-13 -2.62457e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2088 2089 3.2397 -0.235578 -0.105623 -0.00227671 0.064971 -0.10764 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2039 2089 8.24585e-12 -3.05972 -0.0937068 0.0612327 1.81632e-13 -2.62901e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2089 2090 3.23313 -0.235353 -0.105196 -0.00227218 0.0648394 -0.10772 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2040 2090 8.22897e-12 -3.05972 -0.0937068 0.0612327 1.81188e-13 -2.62901e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2090 2091 3.22655 -0.235127 -0.104769 -0.00226764 0.0647077 -0.107799 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2041 2091 8.21032e-12 -3.05972 -0.0937068 0.0612327 1.80744e-13 -2.63345e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2091 2092 3.21997 -0.2349 -0.104343 -0.00226307 0.0645759 -0.107877 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2042 2092 8.19256e-12 -3.05972 -0.0937068 0.0612327 1.80744e-13 -2.63345e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2092 2093 3.21338 -0.234672 -0.103917 -0.00225849 0.064444 -0.107956 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2043 2093 8.17479e-12 -3.05972 -0.0937068 0.0612327 1.803e-13 -2.63789e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2093 2094 3.20679 -0.234443 -0.103492 -0.00225388 0.064312 -0.108034 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2044 2094 8.16414e-12 -3.05972 -0.0937068 0.0612327 1.79856e-13 -2.63789e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2094 2095 3.20019 -0.234213 -0.103067 -0.00224925 0.0641799 -0.108113 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2045 2095 8.14282e-12 -3.05972 -0.0937068 0.0612327 1.79412e-13 -2.64233e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2095 2096 3.19359 -0.233982 -0.102643 -0.0022446 0.0640477 -0.108191 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2046 2096 8.12506e-12 -3.05972 -0.0937068 0.0612327 1.79412e-13 -2.64233e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2096 2097 3.18699 -0.23375 -0.10222 -0.00223993 0.0639154 -0.108269 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2047 2097 8.11262e-12 -3.05972 -0.0937068 0.0612327 1.78968e-13 -2.64677e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2097 2098 3.18038 -0.233517 -0.101797 -0.00223524 0.063783 -0.108347 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2048 2098 8.09308e-12 -3.05972 -0.0937068 0.0612327 1.78524e-13 -2.64677e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2098 2099 3.17376 -0.233283 -0.101375 -0.00223053 0.0636505 -0.108424 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2049 2099 8.07709e-12 -3.05972 -0.0937068 0.0612327 1.78524e-13 -2.65121e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2099 2100 3.16714 -0.233048 -0.100953 -0.0022258 0.063518 -0.108502 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2050 2100 8.0597e-12 -3.05972 -0.0937068 0.0612327 1.7808e-13 -2.65121e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2100 2101 3.16052 -0.232812 -0.100532 -0.00222105 0.0633853 -0.108579 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2051 2101 8.04246e-12 -3.05972 -0.0937068 0.0612327 1.77636e-13 -2.65565e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2101 2102 3.15389 -0.232575 -0.100111 -0.00221628 0.0632525 -0.108657 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2052 2102 8.02647e-12 -3.05972 -0.0937068 0.0612327 1.77192e-13 -2.65565e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2102 2103 3.14726 -0.232336 -0.0996913 -0.00221148 0.0631197 -0.108734 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2053 2103 8.00782e-12 -3.05972 -0.0937068 0.0612327 1.77192e-13 -2.66009e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2103 2104 3.14062 -0.232097 -0.0992719 -0.00220667 0.0629867 -0.10881 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2054 2104 7.99361e-12 -3.05972 -0.0937068 0.0612327 1.76748e-13 -2.66009e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2104 2105 3.13397 -0.231857 -0.0988531 -0.00220184 0.0628537 -0.108887 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2055 2105 7.97584e-12 -3.05972 -0.0937068 0.0612327 1.76303e-13 -2.66454e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2105 2106 3.12732 -0.231616 -0.0984349 -0.00219698 0.0627206 -0.108964 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2056 2106 7.95808e-12 -3.05972 -0.0937068 0.0612327 1.75859e-13 -2.66454e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2106 2107 3.12067 -0.231373 -0.0980173 -0.00219211 0.0625873 -0.10904 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2057 2107 7.94032e-12 -3.05972 -0.0937068 0.0612327 1.75859e-13 -2.66898e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2107 2108 3.11401 -0.23113 -0.0976003 -0.00218721 0.062454 -0.109116 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2058 2108 7.92255e-12 -3.05972 -0.0937068 0.0612327 1.75415e-13 -2.66898e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2108 2109 3.10735 -0.230885 -0.0971839 -0.0021823 0.0623206 -0.109192 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2059 2109 7.90479e-12 -3.05972 -0.0937068 0.0612327 1.74971e-13 -2.67342e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2109 2110 3.10068 -0.23064 -0.0967681 -0.00217736 0.0621871 -0.109268 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2060 2110 7.89058e-12 -3.05972 -0.0937068 0.0612327 1.74971e-13 -2.67342e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2110 2111 3.09401 -0.230394 -0.0963528 -0.0021724 0.0620535 -0.109344 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2061 2111 7.8737e-12 -3.05972 -0.0937068 0.0612327 1.74527e-13 -2.67786e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2111 2112 3.08734 -0.230146 -0.0959382 -0.00216743 0.0619198 -0.109419 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2062 2112 7.85572e-12 -3.05972 -0.0937068 0.0612327 1.74083e-13 -2.67786e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2112 2113 3.08066 -0.229898 -0.0955242 -0.00216243 0.061786 -0.109495 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2063 2113 7.83906e-12 -3.05972 -0.0937068 0.0612327 1.73639e-13 -2.6823e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2113 2114 3.07397 -0.229648 -0.0951108 -0.00215741 0.0616522 -0.10957 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2064 2114 7.82219e-12 -3.05972 -0.0937068 0.0612327 1.73639e-13 -2.6823e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2114 2115 3.06728 -0.229398 -0.094698 -0.00215238 0.0615182 -0.109645 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2065 2115 7.80442e-12 -3.05972 -0.0937068 0.0612327 1.73195e-13 -2.68674e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2115 2116 3.06059 -0.229146 -0.0942859 -0.00214732 0.0613842 -0.10972 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2066 2116 7.78755e-12 -3.05972 -0.0937068 0.0612327 1.72751e-13 -2.68674e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2116 2117 3.05389 -0.228894 -0.0938743 -0.00214224 0.06125 -0.109795 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2067 2117 7.77334e-12 -3.05972 -0.0937068 0.0612327 1.72307e-13 -2.69118e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2117 2118 3.04718 -0.22864 -0.0934634 -0.00213715 0.0611158 -0.109869 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2068 2118 7.75202e-12 -3.05972 -0.0937068 0.0612327 1.72307e-13 -2.69118e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2118 2119 3.04047 -0.228386 -0.0930531 -0.00213203 0.0609815 -0.109944 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2069 2119 7.73603e-12 -3.05972 -0.0937068 0.0612327 1.71863e-13 -2.69118e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2119 2120 3.03376 -0.22813 -0.0926434 -0.00212689 0.060847 -0.110018 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2070 2120 7.72182e-12 -3.05972 -0.0937068 0.0612327 1.71418e-13 -2.69562e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2120 2121 3.02704 -0.227874 -0.0922343 -0.00212173 0.0607125 -0.110092 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2071 2121 7.70051e-12 -3.05972 -0.0937068 0.0612327 1.71418e-13 -2.70006e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2121 2122 3.02032 -0.227616 -0.0918259 -0.00211656 0.0605779 -0.110166 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2072 2122 7.68452e-12 -3.05972 -0.0937068 0.0612327 1.70974e-13 -2.70006e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2122 2123 3.0136 -0.227358 -0.0914181 -0.00211136 0.0604432 -0.11024 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2073 2123 7.66676e-12 -3.05972 -0.0937068 0.0612327 1.7053e-13 -2.70006e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2123 2124 3.00686 -0.227098 -0.0910109 -0.00210614 0.0603085 -0.110313 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2074 2124 7.65166e-12 -3.05972 -0.0937068 0.0612327 1.70086e-13 -2.7045e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2124 2125 3.00013 -0.226838 -0.0906044 -0.00210091 0.0601736 -0.110387 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2075 2125 7.63369e-12 -3.05972 -0.0937068 0.0612327 1.69642e-13 -2.7045e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2125 2126 2.99339 -0.226576 -0.0901985 -0.00209565 0.0600386 -0.11046 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2076 2126 7.61746e-12 -3.05972 -0.0937068 0.0612327 1.69642e-13 -2.70894e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2126 2127 2.98664 -0.226314 -0.0897932 -0.00209037 0.0599036 -0.110533 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2077 2127 7.59925e-12 -3.05972 -0.0937068 0.0612327 1.69198e-13 -2.70894e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2127 2128 2.9799 -0.22605 -0.0893886 -0.00208508 0.0597685 -0.110606 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2078 2128 7.57971e-12 -3.05972 -0.0937068 0.0612327 1.68754e-13 -2.71339e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2128 2129 2.97314 -0.225786 -0.0889847 -0.00207976 0.0596332 -0.110679 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2079 2129 7.5655e-12 -3.05972 -0.0937068 0.0612327 1.6831e-13 -2.71339e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2129 2130 2.96638 -0.22552 -0.0885814 -0.00207442 0.0594979 -0.110751 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2080 2130 7.54596e-12 -3.05972 -0.0937068 0.0612327 1.6831e-13 -2.71783e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2130 2131 2.95962 -0.225254 -0.0881787 -0.00206907 0.0593625 -0.110824 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2081 2131 7.53353e-12 -3.05972 -0.0937068 0.0612327 1.67866e-13 -2.71783e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2131 2132 2.95285 -0.224986 -0.0877767 -0.00206369 0.059227 -0.110896 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2082 2132 7.51577e-12 -3.05972 -0.0937068 0.0612327 1.67422e-13 -2.72227e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2132 2133 2.94608 -0.224718 -0.0873754 -0.0020583 0.0590915 -0.110968 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2083 2133 7.49445e-12 -3.05972 -0.0937068 0.0612327 1.66978e-13 -2.72227e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2133 2134 2.93931 -0.224448 -0.0869747 -0.00205289 0.0589558 -0.11104 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2084 2134 7.48024e-12 -3.05972 -0.0937068 0.0612327 1.66978e-13 -2.72671e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2134 2135 2.93253 -0.224178 -0.0865747 -0.00204745 0.0588201 -0.111112 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2085 2135 7.4607e-12 -3.05972 -0.0937068 0.0612327 1.66533e-13 -2.72671e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2135 2136 2.92574 -0.223907 -0.0861753 -0.002042 0.0586842 -0.111183 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2086 2136 7.44471e-12 -3.05972 -0.0937068 0.0612327 1.66089e-13 -2.72671e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2136 2137 2.91895 -0.223634 -0.0857766 -0.00203653 0.0585483 -0.111255 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2087 2137 7.42673e-12 -3.05972 -0.0937068 0.0612327 1.65645e-13 -2.73115e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2137 2138 2.91216 -0.223361 -0.0853786 -0.00203103 0.0584123 -0.111326 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2088 2138 7.40941e-12 -3.05972 -0.0937068 0.0612327 1.65645e-13 -2.73115e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2138 2139 2.90536 -0.223087 -0.0849812 -0.00202552 0.0582762 -0.111397 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2089 2139 7.39231e-12 -3.05972 -0.0937068 0.0612327 1.65201e-13 -2.73559e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2139 2140 2.89856 -0.222811 -0.0845845 -0.00201999 0.05814 -0.111468 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2090 2140 7.37277e-12 -3.05972 -0.0937068 0.0612327 1.64757e-13 -2.73559e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2140 2141 2.89175 -0.222535 -0.0841885 -0.00201444 0.0580037 -0.111539 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2091 2141 7.35589e-12 -3.05972 -0.0937068 0.0612327 1.64313e-13 -2.74003e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2141 2142 2.88494 -0.222258 -0.0837932 -0.00200887 0.0578674 -0.111609 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2092 2142 7.33991e-12 -3.05972 -0.0937068 0.0612327 1.64313e-13 -2.74003e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2142 2143 2.87813 -0.22198 -0.0833985 -0.00200328 0.0577309 -0.11168 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2093 2143 7.32392e-12 -3.05972 -0.0937068 0.0612327 1.63869e-13 -2.74447e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2143 2144 2.87131 -0.221701 -0.0830046 -0.00199768 0.0575944 -0.11175 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2094 2144 7.3026e-12 -3.05972 -0.0937068 0.0612327 1.63425e-13 -2.74447e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2144 2145 2.86449 -0.221421 -0.0826113 -0.00199205 0.0574578 -0.11182 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2095 2145 7.29017e-12 -3.05972 -0.0937068 0.0612327 1.62981e-13 -2.74447e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2145 2146 2.85766 -0.221139 -0.0822187 -0.0019864 0.0573211 -0.11189 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2096 2146 7.26708e-12 -3.05972 -0.0937068 0.0612327 1.62981e-13 -2.74891e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2146 2147 2.85083 -0.220857 -0.0818268 -0.00198074 0.0571843 -0.11196 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2097 2147 7.25198e-12 -3.05972 -0.0937068 0.0612327 1.62537e-13 -2.75335e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2147 2148 2.84399 -0.220574 -0.0814356 -0.00197505 0.0570474 -0.112029 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2098 2148 7.2351e-12 -3.05972 -0.0937068 0.0612327 1.62093e-13 -2.75335e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2148 2149 2.83715 -0.220291 -0.0810451 -0.00196935 0.0569105 -0.112099 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2099 2149 7.21778e-12 -3.05972 -0.0937068 0.0612327 1.61648e-13 -2.75335e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2149 2150 2.8303 -0.220006 -0.0806552 -0.00196363 0.0567735 -0.112168 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2100 2150 7.20052e-12 -3.05972 -0.0937068 0.0612327 1.61648e-13 -2.75779e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2150 2151 2.82345 -0.21972 -0.0802661 -0.00195788 0.0566363 -0.112237 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2101 2151 7.18359e-12 -3.05972 -0.0937068 0.0612327 1.61204e-13 -2.75779e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2151 2152 2.8166 -0.219433 -0.0798777 -0.00195212 0.0564991 -0.112306 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2102 2152 7.16494e-12 -3.05972 -0.0937068 0.0612327 1.6076e-13 -2.76223e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2152 2153 2.80974 -0.219145 -0.07949 -0.00194634 0.0563618 -0.112375 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2103 2153 7.14806e-12 -3.05972 -0.0937068 0.0612327 1.60316e-13 -2.76223e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2153 2154 2.80288 -0.218856 -0.0791029 -0.00194055 0.0562245 -0.112443 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2104 2154 7.1303e-12 -3.05972 -0.0937068 0.0612327 1.60316e-13 -2.76668e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2154 2155 2.79601 -0.218567 -0.0787166 -0.00193473 0.056087 -0.112512 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2105 2155 7.11253e-12 -3.05972 -0.0937068 0.0612327 1.59872e-13 -2.76668e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2155 2156 2.78914 -0.218276 -0.078331 -0.00192889 0.0559495 -0.11258 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2106 2156 7.09655e-12 -3.05972 -0.0937068 0.0612327 1.59428e-13 -2.77112e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2156 2157 2.78227 -0.217985 -0.0779462 -0.00192304 0.0558118 -0.112648 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2107 2157 7.07701e-12 -3.05972 -0.0937068 0.0612327 1.58984e-13 -2.77112e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2157 2158 2.77539 -0.217692 -0.077562 -0.00191716 0.0556741 -0.112716 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2108 2158 7.05924e-12 -3.05972 -0.0937068 0.0612327 1.58984e-13 -2.77112e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2158 2159 2.76851 -0.217399 -0.0771785 -0.00191127 0.0555364 -0.112784 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2109 2159 7.04325e-12 -3.05972 -0.0937068 0.0612327 1.5854e-13 -2.77556e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2159 2160 2.76162 -0.217104 -0.0767958 -0.00190536 0.0553985 -0.112851 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2110 2160 7.02549e-12 -3.05972 -0.0937068 0.0612327 1.58096e-13 -2.77556e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2160 2161 2.75473 -0.216809 -0.0764138 -0.00189943 0.0552605 -0.112919 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2111 2161 7.00684e-12 -3.05972 -0.0937068 0.0612327 1.57652e-13 -2.78e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2161 2162 2.74783 -0.216513 -0.0760325 -0.00189348 0.0551225 -0.112986 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2112 2162 6.99041e-12 -3.05972 -0.0937068 0.0612327 1.57208e-13 -2.78e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2162 2163 2.74093 -0.216216 -0.075652 -0.00188752 0.0549844 -0.113053 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2113 2163 6.97287e-12 -3.05972 -0.0937068 0.0612327 1.57208e-13 -2.78444e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2163 2164 2.73403 -0.215918 -0.0752721 -0.00188153 0.0548462 -0.11312 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2114 2164 6.95533e-12 -3.05972 -0.0937068 0.0612327 1.56763e-13 -2.78444e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2164 2165 2.72712 -0.215619 -0.074893 -0.00187553 0.0547079 -0.113187 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2115 2165 6.93756e-12 -3.05972 -0.0937068 0.0612327 1.56319e-13 -2.78444e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2165 2166 2.72021 -0.215319 -0.0745147 -0.00186951 0.0545696 -0.113253 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2116 2166 6.92069e-12 -3.05972 -0.0937068 0.0612327 1.55875e-13 -2.78888e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2166 2167 2.7133 -0.215018 -0.0741371 -0.00186346 0.0544311 -0.11332 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2117 2167 6.90292e-12 -3.05972 -0.0937068 0.0612327 1.55875e-13 -2.78888e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2167 2168 2.70638 -0.214716 -0.0737602 -0.00185741 0.0542926 -0.113386 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2118 2168 6.88694e-12 -3.05972 -0.0937068 0.0612327 1.55431e-13 -2.79332e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2168 2169 2.69945 -0.214413 -0.073384 -0.00185133 0.054154 -0.113452 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2119 2169 6.86562e-12 -3.05972 -0.0937068 0.0612327 1.54987e-13 -2.79332e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2169 2170 2.69252 -0.21411 -0.0730086 -0.00184523 0.0540153 -0.113518 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2120 2170 6.84963e-12 -3.05972 -0.0937068 0.0612327 1.54543e-13 -2.79776e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2170 2171 2.68559 -0.213805 -0.0726339 -0.00183912 0.0538765 -0.113583 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2121 2171 6.83009e-12 -3.05972 -0.0937068 0.0612327 1.54099e-13 -2.79776e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2171 2172 2.67866 -0.213499 -0.07226 -0.00183299 0.0537377 -0.113649 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2122 2172 6.8141e-12 -3.05972 -0.0937068 0.0612327 1.54099e-13 -2.79776e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2172 2173 2.67172 -0.213193 -0.0718869 -0.00182684 0.0535988 -0.113714 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2123 2173 6.79634e-12 -3.05972 -0.0937068 0.0612327 1.53655e-13 -2.8022e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2173 2174 2.66477 -0.212886 -0.0715145 -0.00182067 0.0534598 -0.113779 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2124 2174 6.77769e-12 -3.05972 -0.0937068 0.0612327 1.53211e-13 -2.8022e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2174 2175 2.65782 -0.212578 -0.0711428 -0.00181448 0.0533207 -0.113844 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2125 2175 6.7606e-12 -3.05972 -0.0937068 0.0612327 1.52767e-13 -2.80664e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2175 2176 2.65087 -0.212268 -0.0707719 -0.00180828 0.0531815 -0.113909 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2126 2176 6.74261e-12 -3.05972 -0.0937068 0.0612327 1.52767e-13 -2.80664e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2176 2177 2.64392 -0.211958 -0.0704017 -0.00180205 0.0530423 -0.113974 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2127 2177 6.72529e-12 -3.05972 -0.0937068 0.0612327 1.52323e-13 -2.80664e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2177 2178 2.63696 -0.211647 -0.0700324 -0.00179581 0.052903 -0.114039 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2128 2178 6.70575e-12 -3.05972 -0.0937068 0.0612327 1.51879e-13 -2.81108e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2178 2179 2.62999 -0.211336 -0.0696637 -0.00178955 0.0527636 -0.114103 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2129 2179 6.68798e-12 -3.05972 -0.0937068 0.0612327 1.51434e-13 -2.81108e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2179 2180 2.62302 -0.211023 -0.0692959 -0.00178328 0.0526241 -0.114167 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2130 2180 6.67022e-12 -3.05972 -0.0937068 0.0612327 1.51434e-13 -2.81553e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2180 2181 2.61605 -0.210709 -0.0689288 -0.00177698 0.0524846 -0.114231 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2131 2181 6.65246e-12 -3.05972 -0.0937068 0.0612327 1.5099e-13 -2.81553e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2181 2182 2.60908 -0.210395 -0.0685625 -0.00177067 0.0523449 -0.114295 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2132 2182 6.63469e-12 -3.05972 -0.0937068 0.0612327 1.50546e-13 -2.81553e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2182 2183 2.6021 -0.210079 -0.0681969 -0.00176434 0.0522052 -0.114359 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2133 2183 6.61693e-12 -3.05972 -0.0937068 0.0612327 1.50102e-13 -2.81997e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2183 2184 2.59511 -0.209763 -0.0678322 -0.00175799 0.0520655 -0.114422 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2134 2184 6.60005e-12 -3.05972 -0.0937068 0.0612327 1.49658e-13 -2.81997e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2184 2185 2.58813 -0.209446 -0.0674682 -0.00175162 0.0519256 -0.114485 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2135 2185 6.58495e-12 -3.05972 -0.0937068 0.0612327 1.49658e-13 -2.82441e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2185 2186 2.58113 -0.209127 -0.0671049 -0.00174524 0.0517857 -0.114548 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2136 2186 6.56541e-12 -3.05972 -0.0937068 0.0612327 1.49214e-13 -2.82441e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2186 2187 2.57414 -0.208808 -0.0667425 -0.00173884 0.0516456 -0.114611 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2137 2187 6.54743e-12 -3.05972 -0.0937068 0.0612327 1.4877e-13 -2.82885e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2187 2188 2.56714 -0.208489 -0.0663808 -0.00173242 0.0515056 -0.114674 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2138 2188 6.529e-12 -3.05972 -0.0937068 0.0612327 1.48326e-13 -2.82885e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2188 2189 2.56014 -0.208168 -0.06602 -0.00172598 0.0513654 -0.114737 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2139 2189 6.51079e-12 -3.05972 -0.0937068 0.0612327 1.48326e-13 -2.82885e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2189 2190 2.55313 -0.207846 -0.0656599 -0.00171953 0.0512251 -0.114799 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2140 2190 6.49525e-12 -3.05972 -0.0937068 0.0612327 1.47882e-13 -2.83329e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2190 2191 2.54612 -0.207524 -0.0653006 -0.00171306 0.0510848 -0.114862 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2141 2191 6.47571e-12 -3.05972 -0.0937068 0.0612327 1.47438e-13 -2.83329e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2191 2192 2.53911 -0.2072 -0.0649421 -0.00170657 0.0509444 -0.114924 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2142 2192 6.45706e-12 -3.05972 -0.0937068 0.0612327 1.46994e-13 -2.83773e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2192 2193 2.53209 -0.206876 -0.0645844 -0.00170006 0.050804 -0.114986 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2143 2193 6.43752e-12 -3.05972 -0.0937068 0.0612327 1.46549e-13 -2.83773e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2193 2194 2.52507 -0.206551 -0.0642274 -0.00169354 0.0506634 -0.115047 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2144 2194 6.42153e-12 -3.05972 -0.0937068 0.0612327 1.46549e-13 -2.84217e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2194 2195 2.51804 -0.206225 -0.0638713 -0.00168699 0.0505228 -0.115109 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2145 2195 6.40199e-12 -3.05972 -0.0937068 0.0612327 1.46105e-13 -2.84217e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2195 2196 2.51101 -0.205898 -0.063516 -0.00168044 0.0503821 -0.115171 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2146 2196 6.38778e-12 -3.05972 -0.0937068 0.0612327 1.45661e-13 -2.84217e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2196 2197 2.50398 -0.20557 -0.0631615 -0.00167386 0.0502413 -0.115232 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2147 2197 6.36824e-12 -3.05972 -0.0937068 0.0612327 1.45217e-13 -2.84661e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2197 2198 2.49694 -0.205241 -0.0628078 -0.00166727 0.0501005 -0.115293 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2148 2198 6.35136e-12 -3.05972 -0.0937068 0.0612327 1.44773e-13 -2.84661e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2198 2199 2.4899 -0.204912 -0.0624548 -0.00166066 0.0499596 -0.115354 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2149 2199 6.33182e-12 -3.05972 -0.0937068 0.0612327 1.44773e-13 -2.85105e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2199 2200 2.48285 -0.204581 -0.0621027 -0.00165403 0.0498186 -0.115415 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2150 2200 6.31435e-12 -3.05972 -0.0937068 0.0612327 1.44329e-13 -2.85105e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2200 2201 2.47581 -0.20425 -0.0617515 -0.00164738 0.0496775 -0.115475 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2151 2201 6.2963e-12 -3.05972 -0.0937068 0.0612327 1.43885e-13 -2.85105e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2201 2202 2.46875 -0.203918 -0.061401 -0.00164072 0.0495364 -0.115535 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2152 2202 6.27676e-12 -3.05972 -0.0937068 0.0612327 1.43441e-13 -2.85549e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2202 2203 2.4617 -0.203585 -0.0610513 -0.00163404 0.0493952 -0.115596 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2153 2203 6.25988e-12 -3.05972 -0.0937068 0.0612327 1.43441e-13 -2.85549e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2203 2204 2.45464 -0.203251 -0.0607025 -0.00162735 0.0492539 -0.115656 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2154 2204 6.24034e-12 -3.05972 -0.0937068 0.0612327 1.42997e-13 -2.85549e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2204 2205 2.44758 -0.202916 -0.0603544 -0.00162063 0.0491125 -0.115716 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2155 2205 6.22435e-12 -3.05972 -0.0937068 0.0612327 1.42553e-13 -2.85993e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2205 2206 2.44051 -0.202581 -0.0600072 -0.0016139 0.0489711 -0.115775 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2156 2206 6.20659e-12 -3.05972 -0.0937068 0.0612327 1.42109e-13 -2.85993e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2206 2207 2.43344 -0.202245 -0.0596608 -0.00160716 0.0488296 -0.115835 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2157 2207 6.18883e-12 -3.05972 -0.0937068 0.0612327 1.41664e-13 -2.86438e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2207 2208 2.42636 -0.201907 -0.0593153 -0.00160039 0.048688 -0.115894 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2158 2208 6.17284e-12 -3.05972 -0.0937068 0.0612327 1.41664e-13 -2.86438e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2208 2209 2.41929 -0.201569 -0.0589706 -0.00159361 0.0485464 -0.115953 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2159 2209 6.15419e-12 -3.05972 -0.0937068 0.0612327 1.4122e-13 -2.86882e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2209 2210 2.41221 -0.20123 -0.0586267 -0.00158682 0.0484046 -0.116012 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2160 2210 6.13376e-12 -3.05972 -0.0937068 0.0612327 1.40776e-13 -2.86882e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2210 2211 2.40512 -0.200891 -0.0582836 -0.00158 0.0482628 -0.116071 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2161 2211 6.11644e-12 -3.05972 -0.0937068 0.0612327 1.40332e-13 -2.86882e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2211 2212 2.39803 -0.20055 -0.0579413 -0.00157317 0.048121 -0.11613 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2162 2212 6.09779e-12 -3.05972 -0.0937068 0.0612327 1.39888e-13 -2.87326e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2212 2213 2.39094 -0.200209 -0.0575999 -0.00156632 0.047979 -0.116188 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2163 2213 6.0798e-12 -3.05972 -0.0937068 0.0612327 1.39888e-13 -2.87326e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2213 2214 2.38384 -0.199866 -0.0572594 -0.00155946 0.047837 -0.116247 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2164 2214 6.06182e-12 -3.05972 -0.0937068 0.0612327 1.39444e-13 -2.87326e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2214 2215 2.37674 -0.199523 -0.0569196 -0.00155258 0.047695 -0.116305 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2165 2215 6.04317e-12 -3.05972 -0.0937068 0.0612327 1.39e-13 -2.8777e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2215 2216 2.36964 -0.199179 -0.0565808 -0.00154568 0.0475528 -0.116363 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2166 2216 6.0254e-12 -3.05972 -0.0937068 0.0612327 1.38556e-13 -2.8777e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2216 2217 2.36254 -0.198835 -0.0562427 -0.00153877 0.0474106 -0.116421 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2167 2217 6.00586e-12 -3.05972 -0.0937068 0.0612327 1.38112e-13 -2.8777e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2217 2218 2.35543 -0.198489 -0.0559055 -0.00153184 0.0472683 -0.116478 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2168 2218 5.9881e-12 -3.05972 -0.0937068 0.0612327 1.38112e-13 -2.88214e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2218 2219 2.34831 -0.198143 -0.0555692 -0.00152489 0.0471259 -0.116536 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2169 2219 5.97211e-12 -3.05972 -0.0937068 0.0612327 1.37668e-13 -2.88214e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2219 2220 2.34119 -0.197795 -0.0552337 -0.00151793 0.0469835 -0.116593 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2170 2220 5.95257e-12 -3.05972 -0.0937068 0.0612327 1.37224e-13 -2.88658e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2220 2221 2.33407 -0.197447 -0.054899 -0.00151095 0.046841 -0.11665 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2171 2221 5.9357e-12 -3.05972 -0.0937068 0.0612327 1.36779e-13 -2.88658e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2221 2222 2.32695 -0.197098 -0.0545652 -0.00150396 0.0466985 -0.116707 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2172 2222 5.91704e-12 -3.05972 -0.0937068 0.0612327 1.36779e-13 -2.88658e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2222 2223 2.31982 -0.196749 -0.0542323 -0.00149694 0.0465558 -0.116764 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2173 2223 5.89928e-12 -3.05972 -0.0937068 0.0612327 1.36335e-13 -2.89102e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2223 2224 2.31269 -0.196398 -0.0539002 -0.00148992 0.0464131 -0.11682 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2174 2224 5.88063e-12 -3.05972 -0.0937068 0.0612327 1.35891e-13 -2.89102e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2224 2225 2.30556 -0.196047 -0.053569 -0.00148287 0.0462703 -0.116877 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2175 2225 5.86217e-12 -3.05972 -0.0937068 0.0612327 1.35447e-13 -2.89546e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2225 2226 2.29842 -0.195695 -0.0532386 -0.00147581 0.0461275 -0.116933 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2176 2226 5.84333e-12 -3.05972 -0.0937068 0.0612327 1.35003e-13 -2.89546e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2226 2227 2.29128 -0.195342 -0.0529091 -0.00146874 0.0459846 -0.116989 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2177 2227 5.82556e-12 -3.05972 -0.0937068 0.0612327 1.35003e-13 -2.89546e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2227 2228 2.28413 -0.194988 -0.0525805 -0.00146165 0.0458416 -0.117045 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2178 2228 5.80869e-12 -3.05972 -0.0937068 0.0612327 1.34559e-13 -2.8999e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2228 2229 2.27698 -0.194633 -0.0522527 -0.00145454 0.0456986 -0.117101 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2179 2229 5.78826e-12 -3.05972 -0.0937068 0.0612327 1.34115e-13 -2.8999e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2229 2230 2.26983 -0.194278 -0.0519258 -0.00144741 0.0455554 -0.117156 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2180 2230 5.77138e-12 -3.05972 -0.0937068 0.0612327 1.33671e-13 -2.8999e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2230 2231 2.26268 -0.193922 -0.0515998 -0.00144027 0.0454123 -0.117212 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2181 2231 5.75184e-12 -3.05972 -0.0937068 0.0612327 1.33227e-13 -2.90434e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2231 2232 2.25552 -0.193565 -0.0512746 -0.00143312 0.045269 -0.117267 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2182 2232 5.73586e-12 -3.05972 -0.0937068 0.0612327 1.33227e-13 -2.90434e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2232 2233 2.24836 -0.193207 -0.0509504 -0.00142595 0.0451257 -0.117322 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2183 2233 5.71632e-12 -3.05972 -0.0937068 0.0612327 1.32783e-13 -2.90434e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2233 2234 2.24119 -0.192849 -0.050627 -0.00141876 0.0449823 -0.117377 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2184 2234 5.69678e-12 -3.05972 -0.0937068 0.0612327 1.32339e-13 -2.90878e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2234 2235 2.23402 -0.192489 -0.0503044 -0.00141156 0.0448389 -0.117431 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2185 2235 5.6799e-12 -3.05972 -0.0937068 0.0612327 1.31894e-13 -2.90878e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2235 2236 2.22685 -0.192129 -0.0499828 -0.00140434 0.0446954 -0.117486 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2186 2236 5.66036e-12 -3.05972 -0.0937068 0.0612327 1.3145e-13 -2.91323e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2236 2237 2.21968 -0.191768 -0.0496621 -0.0013971 0.0445518 -0.11754 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2187 2237 5.64304e-12 -3.05972 -0.0937068 0.0612327 1.3145e-13 -2.91323e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2237 2238 2.2125 -0.191407 -0.0493422 -0.00138986 0.0444081 -0.117594 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2188 2238 5.62506e-12 -3.05972 -0.0937068 0.0612327 1.31006e-13 -2.91323e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2238 2239 2.20532 -0.191044 -0.0490232 -0.00138259 0.0442644 -0.117648 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2189 2239 5.60707e-12 -3.05972 -0.0937068 0.0612327 1.30562e-13 -2.91767e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2239 2240 2.19813 -0.190681 -0.0487051 -0.00137531 0.0441206 -0.117702 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2190 2240 5.58664e-12 -3.05972 -0.0937068 0.0612327 1.30118e-13 -2.91767e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2240 2241 2.19094 -0.190317 -0.0483879 -0.00136801 0.0439768 -0.117755 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2191 2241 5.57154e-12 -3.05972 -0.0937068 0.0612327 1.29674e-13 -2.91767e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2241 2242 2.18375 -0.189952 -0.0480716 -0.0013607 0.0438329 -0.117809 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2192 2242 5.54934e-12 -3.05972 -0.0937068 0.0612327 1.2923e-13 -2.92211e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2242 2243 2.17656 -0.189587 -0.0477562 -0.00135337 0.0436889 -0.117862 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2193 2243 5.53868e-12 -3.05972 -0.0937068 0.0612327 1.2923e-13 -2.92211e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2243 2244 2.16936 -0.18922 -0.0474416 -0.00134603 0.0435449 -0.117915 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2194 2244 5.51381e-12 -3.05972 -0.0937068 0.0612327 1.28786e-13 -2.92211e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2244 2245 2.16216 -0.188853 -0.047128 -0.00133867 0.0434008 -0.117968 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2195 2245 5.49782e-12 -3.05972 -0.0937068 0.0612327 1.28342e-13 -2.92655e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2245 2246 2.15495 -0.188485 -0.0468153 -0.0013313 0.0432566 -0.118021 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2196 2246 5.4774e-12 -3.05972 -0.0937068 0.0612327 1.27898e-13 -2.92655e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2246 2247 2.14774 -0.188117 -0.0465035 -0.00132391 0.0431124 -0.118073 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2197 2247 5.45874e-12 -3.05972 -0.0937068 0.0612327 1.27898e-13 -2.93099e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2247 2248 2.14053 -0.187747 -0.0461926 -0.00131651 0.0429681 -0.118126 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2198 2248 5.44187e-12 -3.05972 -0.0937068 0.0612327 1.27454e-13 -2.93099e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2248 2249 2.13332 -0.187377 -0.0458826 -0.00130909 0.0428237 -0.118178 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2199 2249 5.42322e-12 -3.05972 -0.0937068 0.0612327 1.2701e-13 -2.93099e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2249 2250 2.1261 -0.187006 -0.0455734 -0.00130166 0.0426793 -0.11823 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2200 2250 5.40451e-12 -3.05972 -0.0937068 0.0612327 1.26565e-13 -2.93543e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2250 2251 2.11888 -0.186634 -0.0452653 -0.00129421 0.0425348 -0.118282 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2201 2251 5.3868e-12 -3.05972 -0.0937068 0.0612327 1.26121e-13 -2.93543e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2251 2252 2.11165 -0.186262 -0.044958 -0.00128675 0.0423903 -0.118334 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2202 2252 5.36993e-12 -3.05972 -0.0937068 0.0612327 1.25677e-13 -2.93543e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2252 2253 2.10443 -0.185889 -0.0446516 -0.00127927 0.0422456 -0.118385 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2203 2253 5.35039e-12 -3.05972 -0.0937068 0.0612327 1.25677e-13 -2.93987e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2253 2254 2.0972 -0.185515 -0.0443461 -0.00127177 0.042101 -0.118436 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2204 2254 5.33174e-12 -3.05972 -0.0937068 0.0612327 1.25233e-13 -2.93987e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2254 2255 2.08996 -0.18514 -0.0440416 -0.00126427 0.0419562 -0.118488 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2205 2255 5.3122e-12 -3.05972 -0.0937068 0.0612327 1.24789e-13 -2.93987e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2255 2256 2.08273 -0.184765 -0.043738 -0.00125674 0.0418114 -0.118538 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2206 2256 5.29354e-12 -3.05972 -0.0937068 0.0612327 1.24345e-13 -2.94431e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2256 2257 2.07549 -0.184389 -0.0434353 -0.00124921 0.0416666 -0.118589 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2207 2257 5.27756e-12 -3.05972 -0.0937068 0.0612327 1.23901e-13 -2.94431e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2257 2258 2.06824 -0.184012 -0.0431335 -0.00124165 0.0415217 -0.11864 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2208 2258 5.25713e-12 -3.05972 -0.0937068 0.0612327 1.23901e-13 -2.94431e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2258 2259 2.061 -0.183634 -0.0428327 -0.00123409 0.0413767 -0.11869 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2209 2259 5.23936e-12 -3.05972 -0.0937068 0.0612327 1.23457e-13 -2.94875e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2259 2260 2.05375 -0.183256 -0.0425327 -0.00122651 0.0412316 -0.118741 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2210 2260 5.21894e-12 -3.05972 -0.0937068 0.0612327 1.23013e-13 -2.94875e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2260 2261 2.0465 -0.182877 -0.0422337 -0.00121891 0.0410865 -0.118791 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2211 2261 5.20206e-12 -3.05972 -0.0937068 0.0612327 1.22569e-13 -2.94875e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2261 2262 2.03924 -0.182497 -0.0419357 -0.0012113 0.0409414 -0.118841 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2212 2262 5.18297e-12 -3.05972 -0.0937068 0.0612327 1.22125e-13 -2.95319e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2262 2263 2.03198 -0.182116 -0.0416385 -0.00120367 0.0407961 -0.11889 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2213 2263 5.16476e-12 -3.05972 -0.0937068 0.0612327 1.2168e-13 -2.95319e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2263 2264 2.02472 -0.181735 -0.0413423 -0.00119603 0.0406508 -0.11894 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2214 2264 5.14566e-12 -3.05972 -0.0937068 0.0612327 1.2168e-13 -2.95319e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2264 2265 2.01746 -0.181353 -0.041047 -0.00118838 0.0405055 -0.118989 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2215 2265 5.12923e-12 -3.05972 -0.0937068 0.0612327 1.21236e-13 -2.95763e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2265 2266 2.01019 -0.18097 -0.0407527 -0.00118071 0.0403601 -0.119038 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2216 2266 5.10791e-12 -3.05972 -0.0937068 0.0612327 1.20792e-13 -2.95763e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2266 2267 2.00292 -0.180587 -0.0404593 -0.00117303 0.0402146 -0.119087 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2217 2267 5.08837e-12 -3.05972 -0.0937068 0.0612327 1.20348e-13 -2.96208e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2267 2268 1.99565 -0.180202 -0.0401669 -0.00116533 0.0400691 -0.119136 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2218 2268 5.0715e-12 -3.05972 -0.0937068 0.0612327 1.19904e-13 -2.96208e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2268 2269 1.98837 -0.179817 -0.0398754 -0.00115762 0.0399235 -0.119185 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2219 2269 5.05374e-12 -3.05972 -0.0937068 0.0612327 1.19904e-13 -2.96208e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2269 2270 1.98109 -0.179432 -0.0395848 -0.0011499 0.0397779 -0.119233 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2220 2270 5.03331e-12 -3.05972 -0.0937068 0.0612327 1.1946e-13 -2.96208e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2270 2271 1.97381 -0.179046 -0.0392952 -0.00114216 0.0396322 -0.119282 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2221 2271 5.01732e-12 -3.05972 -0.0937068 0.0612327 1.19016e-13 -2.96652e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2271 2272 1.96652 -0.178658 -0.0390065 -0.0011344 0.0394864 -0.11933 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2222 2272 4.99778e-12 -3.05972 -0.0937068 0.0612327 1.18572e-13 -2.96652e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2272 2273 1.95923 -0.178271 -0.0387188 -0.00112664 0.0393406 -0.119378 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2223 2273 4.97868e-12 -3.05972 -0.0937068 0.0612327 1.18128e-13 -2.96652e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2273 2274 1.95194 -0.177882 -0.038432 -0.00111885 0.0391947 -0.119426 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2224 2274 4.95981e-12 -3.05972 -0.0937068 0.0612327 1.18128e-13 -2.97096e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2274 2275 1.94465 -0.177493 -0.0381461 -0.00111106 0.0390488 -0.119473 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2225 2275 4.94177e-12 -3.05972 -0.0937068 0.0612327 1.17684e-13 -2.97096e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2275 2276 1.93735 -0.177103 -0.0378613 -0.00110325 0.0389028 -0.119521 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2226 2276 4.92317e-12 -3.05972 -0.0937068 0.0612327 1.1724e-13 -2.97096e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2276 2277 1.93005 -0.176713 -0.0375774 -0.00109543 0.0387567 -0.119568 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2227 2277 4.90452e-12 -3.05972 -0.0937068 0.0612327 1.16795e-13 -2.9754e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2277 2278 1.92275 -0.176322 -0.0372944 -0.00108759 0.0386106 -0.119615 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2228 2278 4.88676e-12 -3.05972 -0.0937068 0.0612327 1.16351e-13 -2.9754e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2278 2279 1.91544 -0.17593 -0.0370124 -0.00107974 0.0384644 -0.119662 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2229 2279 4.86899e-12 -3.05972 -0.0937068 0.0612327 1.15907e-13 -2.9754e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2279 2280 1.90813 -0.175537 -0.0367314 -0.00107188 0.0383182 -0.119708 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2230 2280 4.84679e-12 -3.05972 -0.0937068 0.0612327 1.15907e-13 -2.97984e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2280 2281 1.90082 -0.175144 -0.0364513 -0.001064 0.0381719 -0.119755 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2231 2281 4.82991e-12 -3.05972 -0.0937068 0.0612327 1.15463e-13 -2.97984e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2281 2282 1.89351 -0.17475 -0.0361722 -0.00105611 0.0380256 -0.119801 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2232 2282 4.81037e-12 -3.05972 -0.0937068 0.0612327 1.15019e-13 -2.97984e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2282 2283 1.88619 -0.174355 -0.035894 -0.0010482 0.0378792 -0.119847 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2233 2283 4.79083e-12 -3.05972 -0.0937068 0.0612327 1.14575e-13 -2.97984e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2283 2284 1.87887 -0.17396 -0.0356169 -0.00104028 0.0377328 -0.119893 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2234 2284 4.77485e-12 -3.05972 -0.0937068 0.0612327 1.14131e-13 -2.98428e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2284 2285 1.87155 -0.173564 -0.0353406 -0.00103235 0.0375863 -0.119939 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2235 2285 4.75442e-12 -3.05972 -0.0937068 0.0612327 1.13687e-13 -2.98428e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2285 2286 1.86422 -0.173167 -0.0350654 -0.00102441 0.0374397 -0.119985 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2236 2286 4.73666e-12 -3.05972 -0.0937068 0.0612327 1.13687e-13 -2.98428e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2286 2287 1.85689 -0.17277 -0.0347911 -0.00101645 0.0372931 -0.12003 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2237 2287 4.71789e-12 -3.05972 -0.0937068 0.0612327 1.13243e-13 -2.98872e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2287 2288 1.84956 -0.172371 -0.0345178 -0.00100847 0.0371464 -0.120076 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2238 2288 4.69946e-12 -3.05972 -0.0937068 0.0612327 1.12799e-13 -2.98872e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2288 2289 1.84223 -0.171973 -0.0342455 -0.00100049 0.0369997 -0.120121 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2239 2289 4.68114e-12 -3.05972 -0.0937068 0.0612327 1.12355e-13 -2.98872e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2289 2290 1.83489 -0.171573 -0.0339742 -0.00099249 0.0368529 -0.120166 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2240 2290 4.66205e-12 -3.05972 -0.0937068 0.0612327 1.1191e-13 -2.99316e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2290 2291 1.82755 -0.171173 -0.0337038 -0.000984479 0.0367061 -0.12021 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2241 2291 4.6434e-12 -3.05972 -0.0937068 0.0612327 1.1191e-13 -2.99316e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2291 2292 1.82021 -0.170773 -0.0334345 -0.000976454 0.0365592 -0.120255 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2242 2292 4.62563e-12 -3.05972 -0.0937068 0.0612327 1.11466e-13 -2.99316e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2292 2293 1.81286 -0.170371 -0.0331661 -0.000968416 0.0364122 -0.120299 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2243 2293 4.60521e-12 -3.05972 -0.0937068 0.0612327 1.11022e-13 -2.9976e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2293 2294 1.80552 -0.169969 -0.0328986 -0.000960365 0.0362652 -0.120343 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2244 2294 4.58655e-12 -3.05972 -0.0937068 0.0612327 1.10578e-13 -2.9976e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2294 2295 1.79817 -0.169567 -0.0326322 -0.000952301 0.0361182 -0.120388 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2245 2295 4.56613e-12 -3.05972 -0.0937068 0.0612327 1.10134e-13 -2.9976e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2295 2296 1.79081 -0.169163 -0.0323668 -0.000944224 0.0359711 -0.120431 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2246 2296 4.55014e-12 -3.05972 -0.0937068 0.0612327 1.0969e-13 -3.00204e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2296 2297 1.78346 -0.168759 -0.0321023 -0.000936134 0.0358239 -0.120475 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2247 2297 4.53237e-12 -3.05972 -0.0937068 0.0612327 1.0969e-13 -3.00204e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2297 2298 1.7761 -0.168355 -0.0318389 -0.000928032 0.0356767 -0.120518 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2248 2298 4.5115e-12 -3.05972 -0.0937068 0.0612327 1.09246e-13 -3.00204e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2298 2299 1.76874 -0.167949 -0.0315764 -0.000919917 0.0355295 -0.120562 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2249 2299 4.49263e-12 -3.05972 -0.0937068 0.0612327 1.08802e-13 -3.00204e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2299 2300 1.76137 -0.167543 -0.0313149 -0.000911788 0.0353821 -0.120605 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2250 2300 4.47441e-12 -3.05972 -0.0937068 0.0612327 1.08358e-13 -3.00648e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2300 2301 1.75401 -0.167137 -0.0310544 -0.000903648 0.0352348 -0.120648 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2251 2301 4.4551e-12 -3.05972 -0.0937068 0.0612327 1.07914e-13 -3.00648e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2301 2302 1.74664 -0.16673 -0.0307949 -0.000895494 0.0350874 -0.120691 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2252 2302 4.43645e-12 -3.05972 -0.0937068 0.0612327 1.0747e-13 -3.00648e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2302 2303 1.73927 -0.166322 -0.0305365 -0.000887328 0.0349399 -0.120733 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2253 2303 4.4178e-12 -3.05972 -0.0937068 0.0612327 1.0747e-13 -3.01092e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2303 2304 1.73189 -0.165913 -0.030279 -0.00087915 0.0347924 -0.120776 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2254 2304 4.39915e-12 -3.05972 -0.0937068 0.0612327 1.07025e-13 -3.01092e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2304 2305 1.72452 -0.165504 -0.0300225 -0.000870959 0.0346448 -0.120818 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2255 2305 4.3805e-12 -3.05972 -0.0937068 0.0612327 1.06581e-13 -3.01092e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2305 2306 1.71714 -0.165095 -0.029767 -0.000862755 0.0344972 -0.12086 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2256 2306 4.36184e-12 -3.05972 -0.0937068 0.0612327 1.06137e-13 -3.01092e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2306 2307 1.70975 -0.164684 -0.0295125 -0.000854539 0.0343495 -0.120902 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2257 2307 4.34319e-12 -3.05972 -0.0937068 0.0612327 1.05693e-13 -3.01537e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2307 2308 1.70237 -0.164273 -0.0292591 -0.000846311 0.0342018 -0.120943 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2258 2308 4.32276e-12 -3.05972 -0.0937068 0.0612327 1.05249e-13 -3.01537e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2308 2309 1.69498 -0.163862 -0.0290066 -0.00083807 0.034054 -0.120985 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2259 2309 4.305e-12 -3.05972 -0.0937068 0.0612327 1.05249e-13 -3.01981e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2309 2310 1.68759 -0.16345 -0.0287551 -0.000829818 0.0339062 -0.121026 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2260 2310 4.28679e-12 -3.05972 -0.0937068 0.0612327 1.04805e-13 -3.01981e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2310 2311 1.6802 -0.163037 -0.0285047 -0.000821553 0.0337583 -0.121067 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2261 2311 4.26725e-12 -3.05972 -0.0937068 0.0612327 1.04361e-13 -3.01981e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2311 2312 1.67281 -0.162623 -0.0282552 -0.000813276 0.0336103 -0.121108 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2262 2312 4.24871e-12 -3.05972 -0.0937068 0.0612327 1.03917e-13 -3.01981e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2312 2313 1.66541 -0.162209 -0.0280068 -0.000804986 0.0334624 -0.121149 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2263 2313 4.22962e-12 -3.05972 -0.0937068 0.0612327 1.03473e-13 -3.02425e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2313 2314 1.65801 -0.161795 -0.0277594 -0.000796685 0.0333143 -0.12119 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2264 2314 4.21085e-12 -3.05972 -0.0937068 0.0612327 1.03029e-13 -3.02425e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2314 2315 1.65061 -0.161379 -0.027513 -0.000788372 0.0331663 -0.12123 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2265 2315 4.19176e-12 -3.05972 -0.0937068 0.0612327 1.03029e-13 -3.02425e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2315 2316 1.6432 -0.160964 -0.0272677 -0.000780046 0.0330181 -0.12127 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2266 2316 4.17266e-12 -3.05972 -0.0937068 0.0612327 1.02585e-13 -3.02425e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2316 2317 1.63579 -0.160547 -0.0270233 -0.000771709 0.03287 -0.121311 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2267 2317 4.15579e-12 -3.05972 -0.0937068 0.0612327 1.02141e-13 -3.02869e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2317 2318 1.62839 -0.16013 -0.02678 -0.00076336 0.0327217 -0.12135 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2268 2318 4.13625e-12 -3.05972 -0.0937068 0.0612327 1.01696e-13 -3.02869e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2318 2319 1.62097 -0.159712 -0.0265377 -0.000754999 0.0325735 -0.12139 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2269 2319 4.11671e-12 -3.05972 -0.0937068 0.0612327 1.01252e-13 -3.02869e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2319 2320 1.61356 -0.159294 -0.0262964 -0.000746627 0.0324251 -0.12143 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2270 2320 4.09806e-12 -3.05972 -0.0937068 0.0612327 1.00808e-13 -3.02869e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2320 2321 1.60614 -0.158875 -0.0260561 -0.000738243 0.0322768 -0.121469 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2271 2321 4.07852e-12 -3.05972 -0.0937068 0.0612327 1.00808e-13 -3.03313e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2321 2322 1.59872 -0.158456 -0.0258169 -0.000729847 0.0321284 -0.121508 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2272 2322 4.05986e-12 -3.05972 -0.0937068 0.0612327 1.00364e-13 -3.03313e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2322 2323 1.5913 -0.158036 -0.0255787 -0.000721439 0.0319799 -0.121547 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2273 2323 4.04077e-12 -3.05972 -0.0937068 0.0612327 9.99201e-14 -3.03313e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2323 2324 1.58388 -0.157615 -0.0253415 -0.00071302 0.0318314 -0.121586 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2274 2324 4.02167e-12 -3.05972 -0.0937068 0.0612327 9.9476e-14 -3.03757e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2324 2325 1.57645 -0.157194 -0.0251053 -0.000704589 0.0316828 -0.121625 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2275 2325 4.00285e-12 -3.05972 -0.0937068 0.0612327 9.90319e-14 -3.03757e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2325 2326 1.56902 -0.156773 -0.0248702 -0.000696147 0.0315342 -0.121663 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2276 2326 3.98392e-12 -3.05972 -0.0937068 0.0612327 9.85878e-14 -3.03757e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2326 2327 1.56159 -0.15635 -0.0246362 -0.000687694 0.0313856 -0.121701 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2277 2327 3.96527e-12 -3.05972 -0.0937068 0.0612327 9.85878e-14 -3.03757e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2327 2328 1.55416 -0.155927 -0.0244031 -0.000679229 0.0312369 -0.121739 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2278 2328 3.94529e-12 -3.05972 -0.0937068 0.0612327 9.81437e-14 -3.04201e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2328 2329 1.54672 -0.155504 -0.0241711 -0.000670753 0.0310881 -0.121777 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2279 2329 3.92575e-12 -3.05972 -0.0937068 0.0612327 9.76996e-14 -3.04201e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2329 2330 1.53928 -0.15508 -0.0239401 -0.000662266 0.0309393 -0.121815 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2280 2330 3.90887e-12 -3.05972 -0.0937068 0.0612327 9.72555e-14 -3.04201e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2330 2331 1.53184 -0.154655 -0.0237102 -0.000653767 0.0307905 -0.121852 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2281 2331 3.88756e-12 -3.05972 -0.0937068 0.0612327 9.68114e-14 -3.04201e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2331 2332 1.5244 -0.15423 -0.0234813 -0.000645257 0.0306416 -0.12189 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2282 2332 3.86891e-12 -3.05972 -0.0937068 0.0612327 9.63674e-14 -3.04645e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2332 2333 1.51695 -0.153805 -0.0232535 -0.000636737 0.0304927 -0.121927 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2283 2333 3.85025e-12 -3.05972 -0.0937068 0.0612327 9.63674e-14 -3.04645e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2333 2334 1.50951 -0.153378 -0.0230266 -0.000628205 0.0303437 -0.121964 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2284 2334 3.83249e-12 -3.05972 -0.0937068 0.0612327 9.59233e-14 -3.04645e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2334 2335 1.50206 -0.152952 -0.0228009 -0.000619662 0.0301947 -0.122001 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2285 2335 3.81295e-12 -3.05972 -0.0937068 0.0612327 9.54792e-14 -3.05089e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2335 2336 1.4946 -0.152524 -0.0225762 -0.000611108 0.0300457 -0.122037 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2286 2336 3.79385e-12 -3.05972 -0.0937068 0.0612327 9.50351e-14 -3.05089e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2336 2337 1.48715 -0.152096 -0.0223525 -0.000602543 0.0298965 -0.122074 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2287 2337 3.77498e-12 -3.05972 -0.0937068 0.0612327 9.4591e-14 -3.05089e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2337 2338 1.47969 -0.151668 -0.0221299 -0.000593968 0.0297474 -0.12211 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2288 2338 3.75633e-12 -3.05972 -0.0937068 0.0612327 9.41469e-14 -3.05089e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2338 2339 1.47224 -0.151239 -0.0219083 -0.000585381 0.0295982 -0.122146 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2289 2339 3.73701e-12 -3.05972 -0.0937068 0.0612327 9.41469e-14 -3.05533e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2339 2340 1.46477 -0.150809 -0.0216878 -0.000576784 0.029449 -0.122182 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2290 2340 3.71836e-12 -3.05972 -0.0937068 0.0612327 9.37028e-14 -3.05533e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2340 2341 1.45731 -0.150379 -0.0214683 -0.000568176 0.0292997 -0.122218 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2291 2341 3.69837e-12 -3.05972 -0.0937068 0.0612327 9.32587e-14 -3.05533e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2341 2342 1.44985 -0.149949 -0.0212499 -0.000559558 0.0291504 -0.122253 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2292 2342 3.67972e-12 -3.05972 -0.0937068 0.0612327 9.28146e-14 -3.05977e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2342 2343 1.44238 -0.149517 -0.0210326 -0.000550929 0.029001 -0.122289 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2293 2343 3.66018e-12 -3.05972 -0.0937068 0.0612327 9.23706e-14 -3.05977e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2343 2344 1.43491 -0.149086 -0.0208163 -0.000542289 0.0288516 -0.122324 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2294 2344 3.64242e-12 -3.05972 -0.0937068 0.0612327 9.19265e-14 -3.05977e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2344 2345 1.42744 -0.148654 -0.020601 -0.000533639 0.0287021 -0.122359 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2295 2345 3.62199e-12 -3.05972 -0.0937068 0.0612327 9.14824e-14 -3.05977e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2345 2346 1.41996 -0.148221 -0.0203868 -0.000524979 0.0285526 -0.122394 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2296 2346 3.60334e-12 -3.05972 -0.0937068 0.0612327 9.14824e-14 -3.06422e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2346 2347 1.41249 -0.147788 -0.0201737 -0.000516308 0.0284031 -0.122428 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2297 2347 3.58469e-12 -3.05972 -0.0937068 0.0612327 9.10383e-14 -3.06422e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2347 2348 1.40501 -0.147354 -0.0199617 -0.000507627 0.0282535 -0.122463 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2298 2348 3.56604e-12 -3.05972 -0.0937068 0.0612327 9.05942e-14 -3.06422e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2348 2349 1.39753 -0.146919 -0.0197507 -0.000498935 0.0281039 -0.122497 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2299 2349 3.54672e-12 -3.05972 -0.0937068 0.0612327 9.01501e-14 -3.06422e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2349 2350 1.39005 -0.146485 -0.0195407 -0.000490234 0.0279542 -0.122531 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2300 2350 3.52754e-12 -3.05972 -0.0937068 0.0612327 8.9706e-14 -3.06422e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2350 2351 1.38256 -0.146049 -0.0193319 -0.000481522 0.0278045 -0.122565 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2301 2351 3.5083e-12 -3.05972 -0.0937068 0.0612327 8.92619e-14 -3.06866e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2351 2352 1.37508 -0.145613 -0.0191241 -0.0004728 0.0276548 -0.122599 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2302 2352 3.48832e-12 -3.05972 -0.0937068 0.0612327 8.88178e-14 -3.06866e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2352 2353 1.36759 -0.145177 -0.0189173 -0.000464068 0.027505 -0.122632 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2303 2353 3.47011e-12 -3.05972 -0.0937068 0.0612327 8.88178e-14 -3.06866e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2353 2354 1.3601 -0.14474 -0.0187117 -0.000455325 0.0273552 -0.122665 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2304 2354 3.45235e-12 -3.05972 -0.0937068 0.0612327 8.83738e-14 -3.06866e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2354 2355 1.35261 -0.144303 -0.0185071 -0.000446573 0.0272053 -0.122699 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2305 2355 3.43103e-12 -3.05972 -0.0937068 0.0612327 8.79297e-14 -3.0731e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2355 2356 1.34511 -0.143865 -0.0183036 -0.000437811 0.0270554 -0.122732 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2306 2356 3.41416e-12 -3.05972 -0.0937068 0.0612327 8.74856e-14 -3.0731e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2356 2357 1.33761 -0.143427 -0.0181011 -0.000429039 0.0269055 -0.122764 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2307 2357 3.39373e-12 -3.05972 -0.0937068 0.0612327 8.70415e-14 -3.0731e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2357 2358 1.33012 -0.142988 -0.0178997 -0.000420258 0.0267555 -0.122797 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2308 2358 3.37508e-12 -3.05972 -0.0937068 0.0612327 8.65974e-14 -3.0731e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2358 2359 1.32261 -0.142549 -0.0176994 -0.000411466 0.0266055 -0.122829 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2309 2359 3.3582e-12 -3.05972 -0.0937068 0.0612327 8.65974e-14 -3.07754e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2359 2360 1.31511 -0.142109 -0.0175002 -0.000402665 0.0264554 -0.122862 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2310 2360 3.33555e-12 -3.05972 -0.0937068 0.0612327 8.61533e-14 -3.07754e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2360 2361 1.30761 -0.141668 -0.0173021 -0.000393854 0.0263053 -0.122894 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2311 2361 3.31735e-12 -3.05972 -0.0937068 0.0612327 8.57092e-14 -3.07754e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2361 2362 1.3001 -0.141228 -0.017105 -0.000385034 0.0261551 -0.122926 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2312 2362 3.29836e-12 -3.05972 -0.0937068 0.0612327 8.52651e-14 -3.07754e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2362 2363 1.29259 -0.140786 -0.016909 -0.000376204 0.026005 -0.122957 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2313 2363 3.27915e-12 -3.05972 -0.0937068 0.0612327 8.4821e-14 -3.08198e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2363 2364 1.28508 -0.140345 -0.0167141 -0.000367364 0.0258547 -0.122989 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2314 2364 3.26073e-12 -3.05972 -0.0937068 0.0612327 8.43769e-14 -3.08198e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2364 2365 1.27757 -0.139902 -0.0165203 -0.000358515 0.0257045 -0.12302 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2315 2365 3.24052e-12 -3.05972 -0.0937068 0.0612327 8.43769e-14 -3.08198e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2365 2366 1.27006 -0.13946 -0.0163276 -0.000349657 0.0255542 -0.123051 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2316 2366 3.22142e-12 -3.05972 -0.0937068 0.0612327 8.39329e-14 -3.08198e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2366 2367 1.26254 -0.139017 -0.0161359 -0.000340789 0.0254038 -0.123082 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2317 2367 3.20277e-12 -3.05972 -0.0937068 0.0612327 8.34888e-14 -3.08642e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2367 2368 1.25502 -0.138573 -0.0159454 -0.000331913 0.0252535 -0.123113 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2318 2368 3.18234e-12 -3.05972 -0.0937068 0.0612327 8.30447e-14 -3.08642e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2368 2369 1.2475 -0.138129 -0.0157559 -0.000323026 0.0251031 -0.123144 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2319 2369 3.16369e-12 -3.05972 -0.0937068 0.0612327 8.26006e-14 -3.08642e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2369 2370 1.23998 -0.137684 -0.0155675 -0.000314131 0.0249526 -0.123174 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2320 2370 3.14415e-12 -3.05972 -0.0937068 0.0612327 8.21565e-14 -3.08642e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2370 2371 1.23246 -0.137239 -0.0153802 -0.000305226 0.0248021 -0.123204 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2321 2371 3.1255e-12 -3.05972 -0.0937068 0.0612327 8.17124e-14 -3.09086e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2371 2372 1.22493 -0.136794 -0.015194 -0.000296313 0.0246516 -0.123235 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2322 2372 3.10596e-12 -3.05972 -0.0937068 0.0612327 8.17124e-14 -3.09086e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2372 2373 1.2174 -0.136348 -0.0150089 -0.00028739 0.0245011 -0.123264 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2323 2373 3.08775e-12 -3.05972 -0.0937068 0.0612327 8.12683e-14 -3.09086e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2373 2374 1.20987 -0.135901 -0.0148248 -0.000278459 0.0243505 -0.123294 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2324 2374 3.06821e-12 -3.05972 -0.0937068 0.0612327 8.08242e-14 -3.09086e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2374 2375 1.20234 -0.135455 -0.0146419 -0.000269518 0.0241998 -0.123324 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2325 2375 3.04892e-12 -3.05972 -0.0937068 0.0612327 8.03801e-14 -3.09086e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2375 2376 1.19481 -0.135007 -0.0144601 -0.000260569 0.0240492 -0.123353 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2326 2376 3.0298e-12 -3.05972 -0.0937068 0.0612327 7.99361e-14 -3.09086e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2376 2377 1.18728 -0.134559 -0.0142793 -0.000251611 0.0238985 -0.123382 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2327 2377 3.01048e-12 -3.05972 -0.0937068 0.0612327 7.9492e-14 -3.0953e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2377 2378 1.17974 -0.134111 -0.0140997 -0.000242644 0.0237477 -0.123411 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2328 2378 2.99094e-12 -3.05972 -0.0937068 0.0612327 7.90479e-14 -3.0953e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2378 2379 1.1722 -0.133663 -0.0139211 -0.000233668 0.023597 -0.12344 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2329 2379 2.97229e-12 -3.05972 -0.0937068 0.0612327 7.90479e-14 -3.0953e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2379 2380 1.16466 -0.133214 -0.0137437 -0.000224684 0.0234462 -0.123468 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2330 2380 2.95319e-12 -3.05972 -0.0937068 0.0612327 7.86038e-14 -3.09974e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2380 2381 1.15712 -0.132764 -0.0135674 -0.000215691 0.0232953 -0.123497 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2331 2381 2.93454e-12 -3.05972 -0.0937068 0.0612327 7.81597e-14 -3.09974e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2381 2382 1.14958 -0.132314 -0.0133921 -0.000206689 0.0231445 -0.123525 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2332 2382 2.91589e-12 -3.05972 -0.0937068 0.0612327 7.77156e-14 -3.09974e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2382 2383 1.14203 -0.131864 -0.013218 -0.000197679 0.0229935 -0.123553 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2333 2383 2.89546e-12 -3.05972 -0.0937068 0.0612327 7.72715e-14 -3.09974e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2383 2384 1.13448 -0.131413 -0.0130449 -0.000188661 0.0228426 -0.123581 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2334 2384 2.87548e-12 -3.05972 -0.0937068 0.0612327 7.68274e-14 -3.09974e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2384 2385 1.12694 -0.130962 -0.012873 -0.000179634 0.0226916 -0.123609 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2335 2385 2.85638e-12 -3.05972 -0.0937068 0.0612327 7.63833e-14 -3.10418e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2385 2386 1.11939 -0.13051 -0.0127022 -0.000170599 0.0225406 -0.123636 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2336 2386 2.83795e-12 -3.05972 -0.0937068 0.0612327 7.63833e-14 -3.10418e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2386 2387 1.11183 -0.130058 -0.0125325 -0.000161556 0.0223896 -0.123663 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2337 2387 2.8183e-12 -3.05972 -0.0937068 0.0612327 7.59393e-14 -3.10418e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2387 2388 1.10428 -0.129606 -0.0123638 -0.000152504 0.0222385 -0.123691 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2338 2388 2.79887e-12 -3.05972 -0.0937068 0.0612327 7.54952e-14 -3.10418e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2388 2389 1.09672 -0.129153 -0.0121963 -0.000143444 0.0220874 -0.123717 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2339 2389 2.77933e-12 -3.05972 -0.0937068 0.0612327 7.50511e-14 -3.10418e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2389 2390 1.08917 -0.1287 -0.0120299 -0.000134377 0.0219363 -0.123744 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2340 2390 2.76001e-12 -3.05972 -0.0937068 0.0612327 7.4607e-14 -3.10862e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2390 2391 1.08161 -0.128246 -0.0118647 -0.000125301 0.0217851 -0.123771 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2341 2391 2.74136e-12 -3.05972 -0.0937068 0.0612327 7.41629e-14 -3.10862e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2391 2392 1.07405 -0.127792 -0.0117005 -0.000116217 0.0216339 -0.123797 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2342 2392 2.72271e-12 -3.05972 -0.0937068 0.0612327 7.37188e-14 -3.10862e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2392 2393 1.06649 -0.127338 -0.0115374 -0.000107125 0.0214826 -0.123823 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2343 2393 2.70273e-12 -3.05972 -0.0937068 0.0612327 7.37188e-14 -3.10862e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2393 2394 1.05892 -0.126883 -0.0113755 -9.8025e-05 0.0213314 -0.123849 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2344 2394 2.68496e-12 -3.05972 -0.0937068 0.0612327 7.32747e-14 -3.10862e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2394 2395 1.05136 -0.126427 -0.0112147 -8.89174e-05 0.0211801 -0.123875 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2345 2395 2.66409e-12 -3.05972 -0.0937068 0.0612327 7.28306e-14 -3.10862e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2395 2396 1.04379 -0.125972 -0.0110549 -7.98019e-05 0.0210287 -0.123901 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2346 2396 2.645e-12 -3.05972 -0.0937068 0.0612327 7.23865e-14 -3.11307e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2396 2397 1.03622 -0.125516 -0.0108963 -7.06787e-05 0.0208774 -0.123926 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2347 2397 2.62501e-12 -3.05972 -0.0937068 0.0612327 7.19425e-14 -3.11307e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2397 2398 1.02865 -0.125059 -0.0107389 -6.15479e-05 0.020726 -0.123952 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2348 2398 2.60569e-12 -3.05972 -0.0937068 0.0612327 7.14984e-14 -3.11307e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2398 2399 1.02108 -0.124602 -0.0105825 -5.24094e-05 0.0205745 -0.123977 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2349 2399 2.58682e-12 -3.05972 -0.0937068 0.0612327 7.10543e-14 -3.11307e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2399 2400 1.01351 -0.124145 -0.0104273 -4.32633e-05 0.0204231 -0.124002 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2350 2400 2.56745e-12 -3.05972 -0.0937068 0.0612327 7.10543e-14 -3.11751e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2400 2401 1.00594 -0.123688 -0.0102731 -3.41097e-05 0.0202716 -0.124026 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2351 2401 2.54818e-12 -3.05972 -0.0937068 0.0612327 7.06102e-14 -3.11751e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2401 2402 0.998361 -0.12323 -0.0101201 -2.49486e-05 0.0201201 -0.124051 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2352 2402 2.52931e-12 -3.05972 -0.0937068 0.0612327 7.01661e-14 -3.11751e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2402 2403 0.990784 -0.122771 -0.00996825 -1.57802e-05 0.0199685 -0.124075 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2353 2403 2.50955e-12 -3.05972 -0.0937068 0.0612327 6.9722e-14 -3.11751e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2403 2404 0.983205 -0.122313 -0.00981749 -6.60432e-06 0.019817 -0.124099 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2354 2404 2.48956e-12 -3.05972 -0.0937068 0.0612327 6.92779e-14 -3.11751e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2404 2405 0.975625 -0.121854 -0.00966786 2.57882e-06 0.0196654 -0.124123 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2355 2405 2.4718e-12 -3.05972 -0.0937068 0.0612327 6.88338e-14 -3.11751e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2405 2406 0.968043 -0.121394 -0.00951935 1.17692e-05 0.0195137 -0.124147 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2356 2406 2.45182e-12 -3.05972 -0.0937068 0.0612327 6.83897e-14 -3.12195e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2406 2407 0.96046 -0.120934 -0.00937197 2.09668e-05 0.0193621 -0.124171 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2357 2407 2.43228e-12 -3.05972 -0.0937068 0.0612327 6.83897e-14 -3.12195e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2407 2408 0.952876 -0.120474 -0.00922571 3.01715e-05 0.0192104 -0.124194 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2358 2408 2.41362e-12 -3.05972 -0.0937068 0.0612327 6.79456e-14 -3.12195e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2408 2409 0.94529 -0.120014 -0.00908058 3.93833e-05 0.0190587 -0.124218 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2359 2409 2.39275e-12 -3.05972 -0.0937068 0.0612327 6.75016e-14 -3.12195e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2409 2410 0.937702 -0.119553 -0.00893658 4.86021e-05 0.0189069 -0.124241 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2360 2410 2.37366e-12 -3.05972 -0.0937068 0.0612327 6.70575e-14 -3.12639e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2410 2411 0.930114 -0.119092 -0.00879371 5.7828e-05 0.0187551 -0.124264 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2361 2411 2.35456e-12 -3.05972 -0.0937068 0.0612327 6.66134e-14 -3.12639e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2411 2412 0.922523 -0.11863 -0.00865197 6.70607e-05 0.0186033 -0.124286 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2362 2412 2.33547e-12 -3.05972 -0.0937068 0.0612327 6.61693e-14 -3.12639e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2412 2413 0.914932 -0.118168 -0.00851136 7.63003e-05 0.0184515 -0.124309 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2363 2413 2.31609e-12 -3.05972 -0.0937068 0.0612327 6.57252e-14 -3.12639e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2413 2414 0.907339 -0.117706 -0.00837189 8.55467e-05 0.0182997 -0.124331 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2364 2414 2.29661e-12 -3.05972 -0.0937068 0.0612327 6.57252e-14 -3.12639e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2414 2415 0.899745 -0.117243 -0.00823354 9.47999e-05 0.0181478 -0.124353 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2365 2415 2.27729e-12 -3.05972 -0.0937068 0.0612327 6.52811e-14 -3.12639e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2415 2416 0.892149 -0.11678 -0.00809633 0.00010406 0.0179959 -0.124375 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2366 2416 2.25819e-12 -3.05972 -0.0937068 0.0612327 6.4837e-14 -3.13083e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2416 2417 0.884552 -0.116317 -0.00796025 0.000113326 0.0178439 -0.124397 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2367 2417 2.2391e-12 -3.05972 -0.0937068 0.0612327 6.43929e-14 -3.13083e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2417 2418 0.876954 -0.115854 -0.00782531 0.000122599 0.017692 -0.124419 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2368 2418 2.21956e-12 -3.05972 -0.0937068 0.0612327 6.39488e-14 -3.13083e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2418 2419 0.869354 -0.11539 -0.0076915 0.000131879 0.01754 -0.12444 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2369 2419 2.19957e-12 -3.05972 -0.0937068 0.0612327 6.35048e-14 -3.13083e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2419 2420 0.861753 -0.114925 -0.00755883 0.000141165 0.017388 -0.124461 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2370 2420 2.18137e-12 -3.05972 -0.0937068 0.0612327 6.30607e-14 -3.13083e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2420 2421 0.854151 -0.114461 -0.0074273 0.000150458 0.0172359 -0.124482 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2371 2421 2.16049e-12 -3.05972 -0.0937068 0.0612327 6.30607e-14 -3.13527e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2421 2422 0.846547 -0.113996 -0.00729691 0.000159757 0.0170838 -0.124503 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2372 2422 2.14184e-12 -3.05972 -0.0937068 0.0612327 6.26166e-14 -3.13527e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2422 2423 0.838942 -0.113531 -0.00716765 0.000169062 0.0169318 -0.124524 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2373 2423 2.12186e-12 -3.05972 -0.0937068 0.0612327 6.21725e-14 -3.13527e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2423 2424 0.831336 -0.113065 -0.00703954 0.000178373 0.0167796 -0.124544 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2374 2424 2.10276e-12 -3.05972 -0.0937068 0.0612327 6.17284e-14 -3.13527e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2424 2425 0.823729 -0.112599 -0.00691256 0.000187691 0.0166275 -0.124565 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2375 2425 2.08357e-12 -3.05972 -0.0937068 0.0612327 6.12843e-14 -3.13527e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2425 2426 0.816121 -0.112133 -0.00678673 0.000197015 0.0164753 -0.124585 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2376 2426 2.06413e-12 -3.05972 -0.0937068 0.0612327 6.08402e-14 -3.13527e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2426 2427 0.808511 -0.111667 -0.00666204 0.000206345 0.0163231 -0.124605 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2377 2427 2.04503e-12 -3.05972 -0.0937068 0.0612327 6.03961e-14 -3.13527e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2427 2428 0.8009 -0.1112 -0.00653849 0.000215681 0.0161709 -0.124624 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2378 2428 2.02505e-12 -3.05972 -0.0937068 0.0612327 5.9952e-14 -3.13971e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2428 2429 0.793288 -0.110733 -0.00641608 0.000225023 0.0160187 -0.124644 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2379 2429 2.00595e-12 -3.05972 -0.0937068 0.0612327 5.9952e-14 -3.13971e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2429 2430 0.785674 -0.110265 -0.00629482 0.000234371 0.0158664 -0.124663 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2380 2430 1.98641e-12 -3.05972 -0.0937068 0.0612327 5.9508e-14 -3.13971e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2430 2431 0.77806 -0.109798 -0.00617471 0.000243724 0.0157141 -0.124682 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2381 2431 1.96776e-12 -3.05972 -0.0937068 0.0612327 5.90639e-14 -3.13971e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2431 2432 0.770444 -0.10933 -0.00605574 0.000253084 0.0155618 -0.124701 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2382 2432 1.94689e-12 -3.05972 -0.0937068 0.0612327 5.86198e-14 -3.13971e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2432 2433 0.762827 -0.108862 -0.00593792 0.000262449 0.0154095 -0.12472 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2383 2433 1.92868e-12 -3.05972 -0.0937068 0.0612327 5.81757e-14 -3.14415e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2433 2434 0.755209 -0.108393 -0.00582124 0.00027182 0.0152571 -0.124739 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2384 2434 1.90958e-12 -3.05972 -0.0937068 0.0612327 5.77316e-14 -3.14415e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2434 2435 0.74759 -0.107924 -0.00570571 0.000281197 0.0151048 -0.124757 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2385 2435 1.88916e-12 -3.05972 -0.0937068 0.0612327 5.72875e-14 -3.14415e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2435 2436 0.73997 -0.107455 -0.00559134 0.000290579 0.0149524 -0.124776 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2386 2436 1.87006e-12 -3.05972 -0.0937068 0.0612327 5.72875e-14 -3.14415e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2436 2437 0.732349 -0.106986 -0.00547811 0.000299967 0.0147999 -0.124794 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2387 2437 1.85058e-12 -3.05972 -0.0937068 0.0612327 5.68434e-14 -3.14415e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2437 2438 0.724726 -0.106516 -0.00536603 0.000309361 0.0146475 -0.124812 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2388 2438 1.83115e-12 -3.05972 -0.0937068 0.0612327 5.63993e-14 -3.14415e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2438 2439 0.717103 -0.106046 -0.0052551 0.000318759 0.014495 -0.124829 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2389 2439 1.81211e-12 -3.05972 -0.0937068 0.0612327 5.59552e-14 -3.14415e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2439 2440 0.709478 -0.105576 -0.00514532 0.000328164 0.0143425 -0.124847 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2390 2440 1.79234e-12 -3.05972 -0.0937068 0.0612327 5.55112e-14 -3.14415e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2440 2441 0.701852 -0.105106 -0.00503669 0.000337573 0.01419 -0.124864 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2391 2441 1.77325e-12 -3.05972 -0.0937068 0.0612327 5.50671e-14 -3.14859e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2441 2442 0.694226 -0.104635 -0.00492922 0.000346988 0.0140375 -0.124881 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2392 2442 1.75371e-12 -3.05972 -0.0937068 0.0612327 5.4623e-14 -3.14859e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2442 2443 0.686598 -0.104164 -0.0048229 0.000356408 0.013885 -0.124898 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2393 2443 1.73328e-12 -3.05972 -0.0937068 0.0612327 5.41789e-14 -3.14859e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2443 2444 0.678969 -0.103693 -0.00471773 0.000365833 0.0137324 -0.124915 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2394 2444 1.71463e-12 -3.05972 -0.0937068 0.0612327 5.41789e-14 -3.14859e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2444 2445 0.671339 -0.103221 -0.00461372 0.000375263 0.0135798 -0.124932 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2395 2445 1.69509e-12 -3.05972 -0.0937068 0.0612327 5.37348e-14 -3.14859e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2445 2446 0.663708 -0.102749 -0.00451087 0.000384698 0.0134272 -0.124948 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2396 2446 1.67555e-12 -3.05972 -0.0937068 0.0612327 5.32907e-14 -3.14859e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2446 2447 0.656077 -0.102277 -0.00440917 0.000394138 0.0132746 -0.124964 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2397 2447 1.65645e-12 -3.05972 -0.0937068 0.0612327 5.28466e-14 -3.15303e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2447 2448 0.648444 -0.101805 -0.00430862 0.000403583 0.0131219 -0.12498 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2398 2448 1.63691e-12 -3.05972 -0.0937068 0.0612327 5.24025e-14 -3.15303e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2448 2449 0.64081 -0.101333 -0.00420923 0.000413033 0.0129692 -0.124996 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2399 2449 1.61715e-12 -3.05972 -0.0937068 0.0612327 5.19584e-14 -3.15303e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2449 2450 0.633175 -0.10086 -0.00411101 0.000422488 0.0128166 -0.125012 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2400 2450 1.59773e-12 -3.05972 -0.0937068 0.0612327 5.15143e-14 -3.15303e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2450 2451 0.62554 -0.100387 -0.00401393 0.000431947 0.0126638 -0.125027 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2401 2451 1.57818e-12 -3.05972 -0.0937068 0.0612327 5.10703e-14 -3.15303e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2451 2452 0.617903 -0.0999137 -0.00391802 0.000441412 0.0125111 -0.125043 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2402 2452 1.55875e-12 -3.05972 -0.0937068 0.0612327 5.10703e-14 -3.15303e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2452 2453 0.610265 -0.0994402 -0.00382327 0.000450881 0.0123584 -0.125058 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2403 2453 1.53921e-12 -3.05972 -0.0937068 0.0612327 5.06262e-14 -3.15303e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2453 2454 0.602627 -0.0989666 -0.00372967 0.000460354 0.0122056 -0.125073 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2404 2454 1.51967e-12 -3.05972 -0.0937068 0.0612327 5.01821e-14 -3.15303e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2454 2455 0.594988 -0.0984926 -0.00363724 0.000469832 0.0120528 -0.125087 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2405 2455 1.50013e-12 -3.05972 -0.0937068 0.0612327 4.9738e-14 -3.15747e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2455 2456 0.587347 -0.0980185 -0.00354597 0.000479315 0.0119 -0.125102 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2406 2456 1.48104e-12 -3.05972 -0.0937068 0.0612327 4.92939e-14 -3.15747e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2456 2457 0.579706 -0.0975442 -0.00345586 0.000488801 0.0117472 -0.125116 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2407 2457 1.4615e-12 -3.05972 -0.0937068 0.0612327 4.88498e-14 -3.15747e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2457 2458 0.572064 -0.0970696 -0.00336691 0.000498293 0.0115944 -0.12513 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2408 2458 1.44196e-12 -3.05972 -0.0937068 0.0612327 4.84057e-14 -3.15747e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2458 2459 0.564421 -0.0965948 -0.00327913 0.000507788 0.0114415 -0.125144 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2409 2459 1.4222e-12 -3.05972 -0.0937068 0.0612327 4.84057e-14 -3.15747e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2459 2460 0.556777 -0.0961198 -0.0031925 0.000517288 0.0112887 -0.125158 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2410 2460 1.4031e-12 -3.05972 -0.0937068 0.0612327 4.79616e-14 -3.16192e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2460 2461 0.549133 -0.0956446 -0.00310705 0.000526792 0.0111358 -0.125172 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2411 2461 1.38367e-12 -3.05972 -0.0937068 0.0612327 4.75175e-14 -3.15747e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2461 2462 0.541488 -0.0951692 -0.00302275 0.0005363 0.0109829 -0.125185 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2412 2462 1.36391e-12 -3.05972 -0.0937068 0.0612327 4.70735e-14 -3.16192e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2462 2463 0.533841 -0.0946935 -0.00293962 0.000545812 0.01083 -0.125199 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2413 2463 1.34454e-12 -3.05972 -0.0937068 0.0612327 4.66294e-14 -3.16192e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2463 2464 0.526194 -0.0942177 -0.00285766 0.000555329 0.010677 -0.125212 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2414 2464 1.32494e-12 -3.05972 -0.0937068 0.0612327 4.61853e-14 -3.16192e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2464 2465 0.518547 -0.0937417 -0.00277686 0.000564849 0.0105241 -0.125225 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2415 2465 1.30584e-12 -3.05972 -0.0937068 0.0612327 4.57412e-14 -3.16192e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2465 2466 0.510898 -0.0932654 -0.00269723 0.000574373 0.0103711 -0.125237 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2416 2466 1.2863e-12 -3.05972 -0.0937068 0.0612327 4.52971e-14 -3.16192e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2466 2467 0.503249 -0.092789 -0.00261876 0.000583901 0.0102181 -0.12525 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2417 2467 1.2661e-12 -3.05972 -0.0937068 0.0612327 4.52971e-14 -3.16192e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2467 2468 0.495599 -0.0923124 -0.00254146 0.000593433 0.0100651 -0.125262 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2418 2468 1.24678e-12 -3.05972 -0.0937068 0.0612327 4.4853e-14 -3.16192e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2468 2469 0.487948 -0.0918356 -0.00246533 0.000602968 0.00991213 -0.125274 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2419 2469 1.22746e-12 -3.05972 -0.0937068 0.0612327 4.44089e-14 -3.16636e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2469 2470 0.480296 -0.0913586 -0.00239037 0.000612508 0.00975911 -0.125286 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2420 2470 1.20748e-12 -3.05972 -0.0937068 0.0612327 4.39648e-14 -3.16636e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2470 2471 0.472644 -0.0908815 -0.00231657 0.00062205 0.00960607 -0.125298 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2421 2471 1.18883e-12 -3.05972 -0.0937068 0.0612327 4.35207e-14 -3.16636e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2471 2472 0.464991 -0.0904041 -0.00224395 0.000631597 0.00945302 -0.12531 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2422 2472 1.16862e-12 -3.05972 -0.0937068 0.0612327 4.30767e-14 -3.16636e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2472 2473 0.457337 -0.0899266 -0.00217249 0.000641147 0.00929995 -0.125321 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2423 2473 1.1493e-12 -3.05972 -0.0937068 0.0612327 4.26326e-14 -3.16636e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2473 2474 0.449683 -0.0894489 -0.0021022 0.0006507 0.00914687 -0.125332 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2424 2474 1.12998e-12 -3.05972 -0.0937068 0.0612327 4.21885e-14 -3.16636e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2474 2475 0.442028 -0.088971 -0.00203309 0.000660257 0.00899378 -0.125343 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2425 2475 1.1104e-12 -3.05972 -0.0937068 0.0612327 4.21885e-14 -3.16636e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2475 2476 0.434372 -0.088493 -0.00196514 0.000669817 0.00884067 -0.125354 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2426 2476 1.09074e-12 -3.05972 -0.0937068 0.0612327 4.17444e-14 -3.16636e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2476 2477 0.426716 -0.0880148 -0.00189837 0.00067938 0.00868755 -0.125365 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2427 2477 1.07125e-12 -3.05972 -0.0937068 0.0612327 4.13003e-14 -3.16636e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2477 2478 0.419059 -0.0875364 -0.00183276 0.000688947 0.00853442 -0.125375 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2428 2478 1.0516e-12 -3.05972 -0.0937068 0.0612327 4.08562e-14 -3.1708e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2478 2479 0.411401 -0.0870579 -0.00176833 0.000698517 0.00838127 -0.125385 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2429 2479 1.03251e-12 -3.05972 -0.0937068 0.0612327 4.04121e-14 -3.1708e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2479 2480 0.403743 -0.0865792 -0.00170507 0.00070809 0.00822812 -0.125395 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2430 2480 1.01275e-12 -3.05972 -0.0937068 0.0612327 3.9968e-14 -3.1708e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2480 2481 0.396084 -0.0861004 -0.00164299 0.000717666 0.00807495 -0.125405 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2431 2481 9.9365e-13 -3.05972 -0.0937068 0.0612327 3.95239e-14 -3.1708e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2481 2482 0.388425 -0.0856214 -0.00158207 0.000727245 0.00792176 -0.125415 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2432 2482 9.73888e-13 -3.05972 -0.0937068 0.0612327 3.90799e-14 -3.1708e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2482 2483 0.380765 -0.0851423 -0.00152233 0.000736827 0.00776857 -0.125425 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2433 2483 9.54348e-13 -3.05972 -0.0937068 0.0612327 3.90799e-14 -3.1708e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2483 2484 0.373104 -0.084663 -0.00146377 0.000746412 0.00761537 -0.125434 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2434 2484 9.3503e-13 -3.05972 -0.0937068 0.0612327 3.86358e-14 -3.1708e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2484 2485 0.365443 -0.0841836 -0.00140637 0.000756 0.00746215 -0.125443 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2435 2485 9.15268e-13 -3.05972 -0.0937068 0.0612327 3.81917e-14 -3.1708e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2485 2486 0.357781 -0.0837041 -0.00135016 0.00076559 0.00730892 -0.125452 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2436 2486 8.95728e-13 -3.05972 -0.0937068 0.0612327 3.77476e-14 -3.1708e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2486 2487 0.350119 -0.0832244 -0.00129511 0.000775183 0.00715568 -0.125461 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2437 2487 8.76077e-13 -3.05972 -0.0937068 0.0612327 3.73035e-14 -3.17524e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2487 2488 0.342456 -0.0827446 -0.00124124 0.000784779 0.00700244 -0.125469 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2438 2488 8.56537e-13 -3.05972 -0.0937068 0.0612327 3.68594e-14 -3.17524e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2488 2489 0.334793 -0.0822646 -0.00118855 0.000794378 0.00684918 -0.125478 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2439 2489 8.36831e-13 -3.05972 -0.0937068 0.0612327 3.64153e-14 -3.17524e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2489 2490 0.327129 -0.0817845 -0.00113703 0.000803979 0.00669591 -0.125486 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2440 2490 8.17235e-13 -3.05972 -0.0937068 0.0612327 3.59712e-14 -3.17524e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2490 2491 0.319465 -0.0813043 -0.00108669 0.000813582 0.00654263 -0.125494 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2441 2491 7.97584e-13 -3.05972 -0.0937068 0.0612327 3.59712e-14 -3.17524e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2491 2492 0.3118 -0.080824 -0.00103753 0.000823188 0.00638934 -0.125502 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2442 2492 7.77822e-13 -3.05972 -0.0937068 0.0612327 3.55271e-14 -3.17524e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2492 2493 0.304135 -0.0803435 -0.000989541 0.000832796 0.00623604 -0.12551 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2443 2493 7.59171e-13 -3.05972 -0.0937068 0.0612327 3.5083e-14 -3.17524e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2493 2494 0.296469 -0.079863 -0.000942729 0.000842407 0.00608273 -0.125517 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2444 2494 7.39631e-13 -3.05972 -0.0937068 0.0612327 3.4639e-14 -3.17524e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2494 2495 0.288803 -0.0793823 -0.000897096 0.00085202 0.00592942 -0.125524 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2445 2495 7.19869e-13 -3.05972 -0.0937068 0.0612327 3.41949e-14 -3.17968e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2495 2496 0.281136 -0.0789015 -0.000852639 0.000861635 0.00577609 -0.125532 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2446 2496 7.0044e-13 -3.05972 -0.0937068 0.0612327 3.37508e-14 -3.17968e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2496 2497 0.27347 -0.0784206 -0.00080936 0.000871253 0.00562276 -0.125539 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2447 2497 6.80456e-13 -3.05972 -0.0937068 0.0612327 3.33067e-14 -3.17968e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2497 2498 0.265802 -0.0779396 -0.000767259 0.000880872 0.00546942 -0.125545 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2448 2498 6.61027e-13 -3.05972 -0.0937068 0.0612327 3.28626e-14 -3.17968e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2498 2499 0.258134 -0.0774585 -0.000726337 0.000890493 0.00531607 -0.125552 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 +EDGE3 2449 2499 6.41709e-13 -3.05972 -0.0937068 0.0612327 3.28626e-14 -3.17968e-13 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 100 0 0 100 0 25 diff --git a/examples/Data/sphere_smallnoise.graph b/examples/Data/sphere_smallnoise.graph new file mode 100644 index 000000000..121d73021 --- /dev/null +++ b/examples/Data/sphere_smallnoise.graph @@ -0,0 +1,10847 @@ +VERTEX3 0 18.7381 0 98.2287 0 -0 0 +VERTEX3 1 19.0431 1.63954 98.2211 -0.00241135 0.00245691 0.0227253 +VERTEX3 2 19.3024 1.46516 98.2348 -0.0073934 0.0114248 0.0385095 +VERTEX3 3 19.4696 1.22986 98.2737 -0.0101597 0.010242 0.0436139 +VERTEX3 4 19.697 0.303547 98.2997 -0.00852083 0.00885516 0.0545687 +VERTEX3 5 19.5789 -0.379743 98.3832 -0.00736082 0.0109028 0.0566972 +VERTEX3 6 19.328 -1.14383 98.4195 -0.0303184 0.00646135 0.0658667 +VERTEX3 7 19.0094 -1.9915 98.4898 -0.026699 0.00843884 0.0734272 +VERTEX3 8 18.7529 -2.8681 98.5345 -0.0313252 0.00411628 0.0715125 +VERTEX3 9 18.3629 -3.4453 98.5719 -0.0260115 -0.00323782 0.081969 +VERTEX3 10 18.0513 -3.8475 98.6776 -0.0318878 -0.000172174 0.0894192 +VERTEX3 11 17.54 -3.94508 98.7117 -0.0323191 -0.0056373 0.0985955 +VERTEX3 12 17.0645 -3.83338 98.7999 -0.0333963 -0.00697699 0.091581 +VERTEX3 13 16.4558 -3.45396 98.8986 -0.0231773 0.0104809 0.121622 +VERTEX3 14 15.9229 -2.86382 99.0857 -0.0268982 0.00209767 0.126171 +VERTEX3 15 15.1885 -2.10545 99.0647 -0.0253835 0.00266245 0.14307 +VERTEX3 16 14.5113 -1.23672 99.1655 -0.0243512 0.00633828 0.150758 +VERTEX3 17 13.8832 -0.242326 99.3399 -0.0233449 0.00963607 0.174731 +VERTEX3 18 13.2505 1.11904 99.4251 -0.0224392 0.00946535 0.187379 +VERTEX3 19 12.5924 2.43885 99.4403 -0.02154 0.0104606 0.193732 +VERTEX3 20 11.8083 3.98539 99.5278 -0.0201605 0.0122858 0.22571 +VERTEX3 21 10.9248 5.66426 99.5785 -0.0203364 0.0139431 0.241639 +VERTEX3 22 9.96621 7.48105 99.685 -0.0202533 0.0141297 0.267345 +VERTEX3 23 8.86717 9.44094 99.7319 -0.0217672 0.0209338 0.299055 +VERTEX3 24 7.84805 11.7304 99.7871 -0.0151343 0.0300637 0.335819 +VERTEX3 25 6.75298 14.1789 99.8258 -0.0222049 0.00977758 0.380242 +VERTEX3 26 6.66164 -11.3275 100.544 -0.0348774 0.0258583 -0.450329 +VERTEX3 27 8.18757 -9.18792 100.396 -0.0319172 0.0154049 -0.386265 +VERTEX3 28 9.8547 -7.01838 100.215 -0.0289861 0.0132436 -0.34143 +VERTEX3 29 11.3935 -5.0482 100.044 -0.0212305 0.00839623 -0.322697 +VERTEX3 30 12.8887 -3.21259 99.864 -0.0181839 0.00845826 -0.303685 +VERTEX3 31 14.3689 -1.41408 99.7661 -0.0176336 0.00986848 -0.275464 +VERTEX3 32 15.6414 0.131429 99.5676 -0.0171928 0.010443 -0.241435 +VERTEX3 33 16.9814 1.62681 99.3211 -0.0178572 0.00967744 -0.217815 +VERTEX3 34 18.1532 3.07372 99.1282 -0.0176445 0.00988235 -0.19267 +VERTEX3 35 19.2752 4.23291 98.9086 -0.0181049 0.0100056 -0.170796 +VERTEX3 36 20.4523 5.3459 98.6673 -0.0177775 0.0109792 -0.143551 +VERTEX3 37 21.5701 6.16994 98.4602 -0.0166439 0.0110263 -0.130014 +VERTEX3 38 22.4932 6.99136 98.2554 -0.016624 0.0116879 -0.12521 +VERTEX3 39 23.4018 7.51119 98.0431 -0.0151229 0.0108868 -0.104843 +VERTEX3 40 24.1576 7.91325 97.8702 -0.013317 0.0107001 -0.0771072 +VERTEX3 41 24.8414 8.17505 97.6836 -0.0130127 0.0103971 -0.0902155 +VERTEX3 42 25.3083 8.17358 97.6147 -0.0120062 0.0105253 -0.0876668 +VERTEX3 43 25.8319 7.8319 97.4666 -0.0104065 0.0103863 -0.0667465 +VERTEX3 44 26.0541 7.55701 97.3668 -0.00868694 0.010105 -0.0525759 +VERTEX3 45 26.2512 7.30886 97.1978 -0.00762366 0.0103282 -0.0394376 +VERTEX3 46 26.1181 6.93392 97.1105 -0.00625356 0.0107515 -0.0221595 +VERTEX3 47 25.7894 5.97876 96.9855 -0.00421194 0.0118785 -0.0301238 +VERTEX3 48 25.3781 5.17218 96.8359 -0.00231106 0.0104723 -0.0108145 +VERTEX3 49 24.9278 4.07306 96.8126 -0.00147794 0.0118428 0.00568265 +VERTEX3 50 24.5154 2.14705 96.8328 0.000531641 0.0143275 0.00362636 +VERTEX3 51 24.9377 1.71636 96.8362 0.000458836 0.00133284 0.00691283 +VERTEX3 52 25.2263 0.852695 96.8461 -0.00328711 0.00292652 0.0100214 +VERTEX3 53 25.4724 0.704763 96.9054 -0.00353908 0.00879119 0.0374325 +VERTEX3 54 25.5201 0.766064 96.9592 -0.0134706 0.00879055 0.0411312 +VERTEX3 55 25.4329 -1.02434 96.9932 -0.0129435 0.00717268 0.0351519 +VERTEX3 56 25.2581 -2.05662 97.0357 -0.0147605 0.00518744 0.0364517 +VERTEX3 57 24.9361 -2.49761 97.1333 -0.0304483 0.00695934 0.0539866 +VERTEX3 58 24.5629 -2.66456 97.1506 -0.0282838 0.00705871 0.054551 +VERTEX3 59 24.2557 -3.32287 97.2281 -0.0310153 0.00298143 0.0700066 +VERTEX3 60 23.8654 -3.91999 97.2572 -0.027892 -0.00326376 0.0776848 +VERTEX3 61 23.4823 -3.91511 97.3456 -0.027995 -0.000404544 0.0827778 +VERTEX3 62 22.9837 -3.98946 97.3927 -0.0241689 -0.00658063 0.0897529 +VERTEX3 63 22.4588 -3.4532 97.4894 -0.0290707 0.00270369 0.0966411 +VERTEX3 64 21.8303 -2.6535 97.5345 -0.0316777 0.00335803 0.111628 +VERTEX3 65 21.2376 -1.55993 97.6378 -0.027891 0.00573747 0.12521 +VERTEX3 66 20.5596 -0.558266 97.7363 -0.016786 0.00864771 0.156246 +VERTEX3 67 19.8838 0.541952 97.8151 -0.0238187 0.0158773 0.157195 +VERTEX3 68 19.1843 2.02178 97.8985 -0.0297446 0.00701025 0.173511 +VERTEX3 69 18.5 3.46906 97.919 -0.021413 0.00728889 0.184167 +VERTEX3 70 17.6533 5.20553 97.9837 -0.023219 0.0052847 0.215628 +VERTEX3 71 16.7926 7.04863 98.0052 -0.0182994 0.00419914 0.238596 +VERTEX3 72 15.7916 8.98756 98.0491 -0.0143915 0.0110095 0.264976 +VERTEX3 73 14.6901 11.1309 98.1062 -0.0198685 0.013208 0.304693 +VERTEX3 74 13.4447 13.2672 98.1198 -0.023077 0.0170768 0.325497 +VERTEX3 75 11.9119 16.6733 98.1357 -0.0175844 0.0136989 0.374549 +VERTEX3 76 11.6957 -14.2078 98.859 -0.0269731 0.0197359 -0.446859 +VERTEX3 77 13.7327 -11.1485 98.7505 -0.0276853 0.0148285 -0.370582 +VERTEX3 78 15.4114 -9.09654 98.5503 -0.0200776 0.00949301 -0.357439 +VERTEX3 79 17.0839 -6.9128 98.3455 -0.0139678 0.00307272 -0.315605 +VERTEX3 80 18.5805 -4.94485 98.2337 -0.0174116 0.00964099 -0.300458 +VERTEX3 81 20.0627 -3.09976 98.0757 -0.0159514 0.0117068 -0.261272 +VERTEX3 82 21.4325 -1.20975 97.832 -0.0178905 0.0105611 -0.241944 +VERTEX3 83 22.7292 0.565337 97.6548 -0.0172572 0.0118895 -0.206957 +VERTEX3 84 23.9359 2.11851 97.4518 -0.0157039 0.00783226 -0.186477 +VERTEX3 85 25.1764 3.49742 97.189 -0.0197331 0.0105972 -0.164414 +VERTEX3 86 26.2828 4.88098 96.9558 -0.0175524 0.00965658 -0.13204 +VERTEX3 87 27.3216 6.00114 96.7147 -0.0160848 0.0118506 -0.121016 +VERTEX3 88 28.2935 6.86364 96.5102 -0.0173208 0.010394 -0.110139 +VERTEX3 89 29.1403 7.16356 96.3462 -0.0141689 0.00981626 -0.0905138 +VERTEX3 90 29.93 7.63017 96.1377 -0.0130906 0.00872201 -0.0851961 +VERTEX3 91 30.5247 7.96979 95.9731 -0.0113708 0.0103857 -0.0723159 +VERTEX3 92 31.0742 8.17089 95.9158 -0.011943 0.0102842 -0.0651156 +VERTEX3 93 31.5137 8.1664 95.7869 -0.0091081 0.00909655 -0.0627943 +VERTEX3 94 31.8569 8.46609 95.6654 -0.00714208 0.00903537 -0.0265849 +VERTEX3 95 31.9899 8.68866 95.5586 -0.00858013 0.0108937 -0.0106073 +VERTEX3 96 31.8433 7.78904 95.4472 -0.00210287 0.00807332 -0.00423543 +VERTEX3 97 31.6484 7.33843 95.321 -0.00266957 0.00724898 -0.0107552 +VERTEX3 98 31.3174 7.02041 95.2156 -0.000103182 0.00818872 0.0215139 +VERTEX3 99 30.9799 5.58016 95.2658 0.000349446 0.0122205 0.0105508 +VERTEX3 100 30.4115 4.4518 95.1409 -0.00733057 0.0118369 0.00939817 +VERTEX3 101 31.0979 3.80369 95.1553 -0.00330977 0.0144393 0.0334789 +VERTEX3 102 31.1815 1.54179 95.1747 0.000276712 0.00101047 0.0115908 +VERTEX3 103 31.307 -0.132339 95.1948 -0.00455116 0.00420414 0.0027018 +VERTEX3 104 31.3521 -0.221947 95.2609 -0.00612114 0.00963425 0.0313164 +VERTEX3 105 31.2343 -0.960116 95.2491 -0.0114691 0.0109294 0.0370107 +VERTEX3 106 30.9344 -2.04778 95.3158 -0.0137909 0.00925146 0.0315664 +VERTEX3 107 30.7016 -3.44835 95.3832 -0.0199873 0.00289646 0.0229635 +VERTEX3 108 30.3169 -3.88218 95.4598 -0.0322434 0.00571897 0.0383342 +VERTEX3 109 29.9794 -3.29521 95.4485 -0.0300729 0.0057917 0.0578236 +VERTEX3 110 29.5992 -3.91519 95.54 -0.0309675 0.00416479 0.060503 +VERTEX3 111 29.1146 -3.95674 95.545 -0.0286037 -0.000682102 0.0780192 +VERTEX3 112 28.6817 -3.58002 95.6102 -0.025824 0.0064369 0.0829424 +VERTEX3 113 28.2494 -3.33123 95.6415 -0.0289705 0.00254784 0.0839666 +VERTEX3 114 27.6921 -2.98007 95.7282 -0.0236726 0.000599134 0.0919779 +VERTEX3 115 27.0235 -1.26194 95.7816 -0.0256379 0.0070606 0.123469 +VERTEX3 116 26.4697 -0.269902 95.8745 -0.0288758 0.00743495 0.128328 +VERTEX3 117 25.7676 1.22429 95.9507 -0.0215253 0.0157407 0.156737 +VERTEX3 118 25.0738 2.65035 95.9927 -0.0256493 0.0148382 0.158228 +VERTEX3 119 24.3393 4.21613 96.0715 -0.0225589 0.0051257 0.18621 +VERTEX3 120 23.518 6.19188 96.0795 -0.0215945 0.00899906 0.210802 +VERTEX3 121 22.5582 8.21755 96.0766 -0.0206737 0.00488189 0.229891 +VERTEX3 122 21.468 10.4341 96.1437 -0.0224599 0.0122417 0.267621 +VERTEX3 123 20.3043 12.5752 96.1509 -0.0161611 0.0149012 0.284652 +VERTEX3 124 18.9626 14.7846 96.1714 -0.0194037 0.0132889 0.303179 +VERTEX3 125 17.7327 15.057 96.1763 -0.0121755 0.0133191 0.291129 +VERTEX3 126 17.1526 -14.4063 96.8277 -0.0244446 0.00739059 -0.368134 +VERTEX3 127 18.9799 -13.1478 96.7234 -0.0182744 0.00846097 -0.365577 +VERTEX3 128 20.8783 -10.905 96.5543 -0.0195324 0.00681554 -0.345683 +VERTEX3 129 22.5703 -8.71185 96.3838 -0.0182961 0.00986199 -0.310825 +VERTEX3 130 24.1453 -6.56332 96.2322 -0.0148158 0.0120787 -0.292349 +VERTEX3 131 25.6768 -4.49152 96.034 -0.017234 0.0107222 -0.263094 +VERTEX3 132 27.0845 -2.39564 95.8279 -0.0189898 0.0116002 -0.229641 +VERTEX3 133 28.3672 -0.529281 95.5605 -0.0159257 0.00545177 -0.203712 +VERTEX3 134 29.6394 1.52757 95.3757 -0.0194406 0.0106727 -0.172636 +VERTEX3 135 30.8921 3.20772 95.1005 -0.0187285 0.00873204 -0.155577 +VERTEX3 136 31.9762 4.84145 94.8708 -0.0155924 0.011527 -0.127137 +VERTEX3 137 32.9662 5.77529 94.6296 -0.0189144 0.0102638 -0.113076 +VERTEX3 138 33.9099 6.41449 94.4373 -0.0153641 0.00850889 -0.107168 +VERTEX3 139 34.8426 7.01592 94.215 -0.0156515 0.00726808 -0.0929324 +VERTEX3 140 35.4118 7.76243 94.0772 -0.0111209 0.0105036 -0.0691761 +VERTEX3 141 36.1092 8.18389 93.9663 -0.0132564 0.00993041 -0.0643384 +VERTEX3 142 36.6721 8.16846 93.8224 -0.00966773 0.0073055 -0.0645549 +VERTEX3 143 37.1581 9.29979 93.7426 -0.00839045 0.00836085 -0.0377757 +VERTEX3 144 37.5831 9.60526 93.6417 -0.0104634 0.00997669 -0.00324379 +VERTEX3 145 37.558 9.0258 93.5309 -0.00216952 0.0070321 -0.0048974 +VERTEX3 146 37.5242 8.54219 93.4052 -0.00327091 0.0036437 -0.00883219 +VERTEX3 147 37.4954 8.30516 93.3466 -0.00166914 0.00646641 0.00728159 +VERTEX3 148 37.2607 7.40863 93.3253 -0.00259922 0.0103178 0.00037836 +VERTEX3 149 36.8616 6.01074 93.2331 -0.00632169 0.0126778 0.00435345 +VERTEX3 150 36.2678 5.53456 93.0843 -0.025248 0.00346207 0.00809319 +VERTEX3 151 36.8649 5.02302 93.1417 -0.00972696 0.0106343 0.0258219 +VERTEX3 152 37.156 3.91249 93.1654 -0.00281496 0.0118514 0.031775 +VERTEX3 153 37.1018 0.890491 93.184 -0.00110979 0.00186807 0.0190227 +VERTEX3 154 37.0254 -0.689558 93.113 -0.00858903 0.00695249 0.0175215 +VERTEX3 155 36.8031 -2.01294 93.183 -0.0139687 0.000688787 0.0221209 +VERTEX3 156 36.6302 -1.6406 93.1629 -0.0233927 0.00397166 0.043387 +VERTEX3 157 36.2216 -3.60523 93.2734 -0.0168067 0.00770949 0.0206717 +VERTEX3 158 35.9986 -4.96612 93.368 -0.0259719 0.00259378 0.0175894 +VERTEX3 159 35.5304 -4.92109 93.3916 -0.0322047 0.00599191 0.0314009 +VERTEX3 160 35.1197 -3.51701 93.3557 -0.0328336 0.00522108 0.0724699 +VERTEX3 161 34.6663 -3.60332 93.362 -0.0319687 0.00795682 0.0671392 +VERTEX3 162 34.1193 -3.22954 93.3979 -0.0291492 0.00250004 0.076752 +VERTEX3 163 33.7626 -3.57626 93.4619 -0.0230928 0.00341402 0.070179 +VERTEX3 164 33.3681 -3.44988 93.5474 -0.0327331 0.00721935 0.0753668 +VERTEX3 165 32.7966 -2.15741 93.5858 -0.021467 0.00551433 0.088741 +VERTEX3 166 32.1991 -0.331191 93.6497 -0.0238498 0.0132423 0.12405 +VERTEX3 167 31.5715 1.10197 93.6873 -0.0294406 0.00889597 0.130206 +VERTEX3 168 30.8228 2.95316 93.7561 -0.0331277 0.0155968 0.149866 +VERTEX3 169 30.0489 4.81832 93.7601 -0.023877 0.0108186 0.178418 +VERTEX3 170 29.1668 7.09719 93.8701 -0.0163594 0.0175811 0.211058 +VERTEX3 171 28.1379 9.44028 93.8253 -0.0170904 0.017475 0.231264 +VERTEX3 172 27.0585 11.7551 93.8225 -0.0214148 0.00783437 0.255882 +VERTEX3 173 25.7636 14.2517 93.8684 -0.0189599 0.00771667 0.289402 +VERTEX3 174 24.3318 16.7325 93.7969 -0.00964824 0.0111545 0.306263 +VERTEX3 175 22.528 18.6209 93.7871 -0.0185982 0.0150742 0.328539 +VERTEX3 176 22.0456 -16.1705 94.5646 -0.018547 0.00816572 -0.34854 +VERTEX3 177 24.1531 -15.3887 94.4134 -0.0144201 0.00617665 -0.363904 +VERTEX3 178 26.1557 -12.9154 94.2797 -0.0180697 0.00793879 -0.338244 +VERTEX3 179 27.9325 -10.4569 94.0593 -0.0153478 0.0108136 -0.311328 +VERTEX3 180 29.5587 -8.02761 93.8519 -0.017022 0.0102683 -0.28203 +VERTEX3 181 31.1671 -5.39307 93.6011 -0.0209 0.012699 -0.248507 +VERTEX3 182 32.5488 -3.22304 93.4257 -0.0147168 0.00551401 -0.217202 +VERTEX3 183 33.853 -1.16682 93.1889 -0.0208794 0.0103585 -0.196666 +VERTEX3 184 35.1658 0.923973 92.9078 -0.0191762 0.00758819 -0.173286 +VERTEX3 185 36.3775 2.80367 92.6915 -0.0152731 0.0106402 -0.147626 +VERTEX3 186 37.4885 4.62995 92.4578 -0.0198137 0.0102643 -0.12416 +VERTEX3 187 38.4413 5.93657 92.2114 -0.0147303 0.0101725 -0.100396 +VERTEX3 188 39.3406 6.37862 91.9725 -0.0163142 0.00634806 -0.090481 +VERTEX3 189 40.115 7.2008 91.8244 -0.0113768 0.0090775 -0.0817062 +VERTEX3 190 40.8237 7.9458 91.672 -0.0139457 0.0095102 -0.0662515 +VERTEX3 191 41.4888 8.65839 91.5238 -0.0102748 0.0069031 -0.0580508 +VERTEX3 192 42.1019 9.88137 91.4392 -0.00926486 0.00764163 -0.0383765 +VERTEX3 193 42.7271 10.646 91.3311 -0.011681 0.00869893 -0.00486813 +VERTEX3 194 42.9601 9.6259 91.2596 -0.00574842 0.00831312 -0.0262822 +VERTEX3 195 42.9607 9.48173 91.1788 -0.00767549 0.00149152 -0.00738801 +VERTEX3 196 43.2733 8.99865 91.1021 -0.00179586 0.00463512 -0.0180911 +VERTEX3 197 43.3865 7.73204 91.0724 -0.00351333 0.00700084 -0.016824 +VERTEX3 198 43.2091 6.72635 90.9602 -0.00804303 0.0101448 -0.0175351 +VERTEX3 199 42.6864 6.06131 90.9231 -0.0204641 0.00211402 -0.00958039 +VERTEX3 200 42.0493 5.98768 90.8281 -0.0258122 -0.00352534 0.0112084 +VERTEX3 201 42.4448 6.11614 90.7872 -0.0209057 0.000244279 0.0348737 +VERTEX3 202 42.7911 6.08794 90.7698 -0.00996632 0.00951632 0.0411544 +VERTEX3 203 42.8355 3.80596 90.7647 -0.00473647 0.0111743 0.0493289 +VERTEX3 204 42.4877 -0.613564 90.7466 -0.00207197 0.00168505 0.0260488 +VERTEX3 205 42.1735 -3.02592 90.7744 -0.00872064 0.00756572 0.00354301 +VERTEX3 206 41.9967 -2.6619 90.8262 -0.00747492 0.013584 0.0266514 +VERTEX3 207 41.6952 -2.96483 90.8084 -0.0164887 0.0101264 0.0320374 +VERTEX3 208 41.2774 -4.70711 90.8524 -0.0144553 0.0113441 0.024693 +VERTEX3 209 40.9951 -5.86584 90.8993 -0.026856 0.00487047 0.0138285 +VERTEX3 210 40.3822 -4.55055 90.9268 -0.0301713 0.00669348 0.0428715 +VERTEX3 211 39.9516 -4.02476 90.8042 -0.0374017 0.00495706 0.0550349 +VERTEX3 212 39.5094 -3.76336 90.9046 -0.0313426 0.010312 0.0628488 +VERTEX3 213 39.0044 -2.67473 90.8721 -0.0239327 0.00224738 0.0718391 +VERTEX3 214 38.7381 -3.37271 90.9461 -0.028035 0.00291263 0.0751641 +VERTEX3 215 38.2876 -2.55936 91.0295 -0.0314697 0.0106547 0.0793077 +VERTEX3 216 37.6925 -1.16076 91.0717 -0.0155103 0.0131703 0.0989161 +VERTEX3 217 37.1588 0.55877 91.0731 -0.0257954 0.00647873 0.116135 +VERTEX3 218 36.3131 3.30824 91.126 -0.0252985 0.0122561 0.146996 +VERTEX3 219 35.5933 5.1726 91.1751 -0.0256257 0.016561 0.171313 +VERTEX3 220 34.7089 7.3932 91.1708 -0.0223948 0.0189361 0.196181 +VERTEX3 221 33.7794 9.62474 91.2488 -0.0198814 0.0174494 0.206621 +VERTEX3 222 32.585 12.7319 91.1972 -0.0171336 0.00606898 0.257863 +VERTEX3 223 31.1626 15.7521 91.1704 -0.0112738 0.0181165 0.288665 +VERTEX3 224 29.5695 18.9818 91.1538 -0.0157337 0.0101569 0.323906 +VERTEX3 225 27.184 24.4568 91.046 -0.00731085 0.0265293 0.398136 +VERTEX3 226 26.2692 -23.1299 92.0767 -0.0165918 -0.0018507 -0.429514 +VERTEX3 227 29.1756 -17.9157 91.8177 -0.0200508 0.0064862 -0.3658 +VERTEX3 228 31.3558 -14.597 91.6035 -0.0151194 0.0084496 -0.328375 +VERTEX3 229 33.2601 -11.7451 91.3588 -0.0190942 0.0106214 -0.295442 +VERTEX3 230 34.9307 -8.65991 91.0775 -0.0178334 0.0124084 -0.256464 +VERTEX3 231 36.4247 -6.4145 90.8897 -0.0156864 0.0101529 -0.23383 +VERTEX3 232 37.8846 -3.58911 90.7159 -0.0212188 0.00970111 -0.2043 +VERTEX3 233 39.1733 -1.60256 90.4066 -0.0196651 0.00785152 -0.188822 +VERTEX3 234 40.527 1.83738 90.1429 -0.0152096 0.0108924 -0.146622 +VERTEX3 235 41.6245 3.59952 89.8858 -0.0198035 0.0101814 -0.119802 +VERTEX3 236 42.6213 5.48164 89.6239 -0.0156348 0.0102529 -0.0983248 +VERTEX3 237 43.6469 5.18 89.4398 -0.0172803 0.00740659 -0.115 +VERTEX3 238 44.3539 5.63772 89.219 -0.0127776 0.00739459 -0.102402 +VERTEX3 239 45.193 7.45937 89.0758 -0.0140002 0.00722082 -0.0792281 +VERTEX3 240 45.9657 8.16232 88.9261 -0.0118492 0.00476766 -0.0623407 +VERTEX3 241 46.6868 9.45313 88.8168 -0.0111335 0.00704082 -0.052036 +VERTEX3 242 47.4476 11.2507 88.6801 -0.0107415 0.00913278 -0.0185667 +VERTEX3 243 47.8529 9.80544 88.6305 -0.00842304 0.00836716 -0.0337021 +VERTEX3 244 48.1177 9.77475 88.5366 -0.00311681 -0.00104574 -0.031711 +VERTEX3 245 48.546 9.33722 88.4759 -0.000639106 0.00427005 -0.0353251 +VERTEX3 246 49.0739 8.43625 88.5279 -0.00176567 0.00596916 -0.0318445 +VERTEX3 247 49.0006 7.60564 88.3814 -0.00776272 0.0116327 -0.0325183 +VERTEX3 248 48.7965 6.82653 88.3341 -0.0161005 0.00841758 -0.0235092 +VERTEX3 249 48.3504 6.38894 88.2829 -0.0216175 0.00343137 -0.00267015 +VERTEX3 250 47.7871 6.90949 88.2467 -0.0170413 -0.00771353 0.0237798 +VERTEX3 251 47.824 6.53193 88.1284 -0.018816 -0.00590621 0.0290749 +VERTEX3 252 48.1577 7.97313 88.0506 -0.0156694 -0.00400866 0.0599835 +VERTEX3 253 48.206 6.72145 88.0359 -0.0120049 0.00766364 0.0603658 +VERTEX3 254 47.983 3.47606 88.028 -0.00564696 0.00991443 0.0617474 +VERTEX3 255 47.4745 -1.53616 88.0254 -0.0031495 0.00124759 0.0334062 +VERTEX3 256 47.1206 -3.4936 88.0047 -0.0126309 0.00894819 0.014046 +VERTEX3 257 46.7981 -3.55168 88.0596 -0.0136643 0.00730151 0.0207311 +VERTEX3 258 46.4821 -3.60253 87.9682 -0.0240055 0.0033672 0.0338751 +VERTEX3 259 45.8736 -6.99354 88.0368 -0.0240007 0.00217524 0.00142332 +VERTEX3 260 45.5624 -6.63014 88.0454 -0.0324391 0.00563522 0.00849053 +VERTEX3 261 45.0402 -5.54552 88.0795 -0.0314893 0.00899855 0.0424069 +VERTEX3 262 44.6278 -3.61351 87.981 -0.0365982 0.00364569 0.0623058 +VERTEX3 263 44.1384 -3.31822 88.0574 -0.0300874 0.0110131 0.0666091 +VERTEX3 264 43.7273 -2.04614 88.0062 -0.0234442 0.00720599 0.0856983 +VERTEX3 265 43.4595 -2.36662 88.0767 -0.0297064 0.00953527 0.0898884 +VERTEX3 266 42.9 -1.40723 88.1179 -0.0221175 0.00501959 0.0886559 +VERTEX3 267 42.2881 0.461852 88.1295 -0.0209767 0.0106945 0.115893 +VERTEX3 268 41.7794 1.92878 88.1921 -0.0274977 0.0118375 0.113074 +VERTEX3 269 40.8137 5.60694 88.1643 -0.0228177 0.0163788 0.157891 +VERTEX3 270 40.1614 7.34311 88.2539 -0.0210596 0.0203325 0.179144 +VERTEX3 271 38.9845 10.2915 88.2206 -0.020733 0.0216654 0.217714 +VERTEX3 272 37.9525 12.8701 88.269 -0.0199978 0.0136043 0.226518 +VERTEX3 273 36.4547 16.8091 88.1799 -0.0151305 0.00852438 0.282264 +VERTEX3 274 34.8469 20.6579 88.1273 -0.00912609 0.0226782 0.323818 +VERTEX3 275 32.9775 25.5154 88.0767 -0.0152005 0.0214195 0.382066 +VERTEX3 276 31.8114 -24.4822 89.0724 -0.0207859 -0.0106072 -0.421882 +VERTEX3 277 34.3552 -19.8472 88.8562 -0.0178365 0.00693785 -0.364299 +VERTEX3 278 36.4165 -16.2755 88.6063 -0.0211672 0.00863163 -0.322221 +VERTEX3 279 38.4511 -12.3619 88.3403 -0.0153426 0.0126034 -0.267863 +VERTEX3 280 40.0787 -9.4811 88.0625 -0.0160568 0.0135352 -0.24923 +VERTEX3 281 41.5946 -6.67104 87.8032 -0.0208137 0.00863237 -0.213 +VERTEX3 282 42.8998 -4.4716 87.5928 -0.0205152 0.00798031 -0.206696 +VERTEX3 283 44.4531 0.0878576 87.2821 -0.0157226 0.0116036 -0.155897 +VERTEX3 284 45.4809 2.35727 87.0229 -0.0187623 0.0091144 -0.122535 +VERTEX3 285 46.5344 3.7684 86.7867 -0.0180181 0.0100143 -0.113321 +VERTEX3 286 47.5569 4.70341 86.5341 -0.0146926 0.00886279 -0.100293 +VERTEX3 287 48.295 4.73445 86.3357 -0.0143244 0.00603333 -0.119497 +VERTEX3 288 49.2738 6.86687 86.1393 -0.0126632 0.00531304 -0.0843809 +VERTEX3 289 50.0691 7.38357 85.9993 -0.0153552 0.00386585 -0.086006 +VERTEX3 290 50.926 9.37286 85.8536 -0.00861199 0.00569045 -0.0454257 +VERTEX3 291 51.7816 11.3144 85.743 -0.0136382 0.00460322 -0.0201641 +VERTEX3 292 52.2021 10.8973 85.6603 -0.00808742 0.00633879 -0.0291576 +VERTEX3 293 52.6698 9.74307 85.5788 -0.00121572 -0.000323863 -0.0523786 +VERTEX3 294 53.3129 9.52836 85.504 -0.00182236 0.00313452 -0.0383241 +VERTEX3 295 54.2103 8.85963 85.5466 0.00376076 -0.00204448 -0.0545593 +VERTEX3 296 54.2246 8.72837 85.3804 -0.00429423 0.012428 -0.0454551 +VERTEX3 297 54.4387 6.78057 85.5171 -0.00753946 0.00434939 -0.0518757 +VERTEX3 298 54.2998 7.04302 85.3524 -0.0187441 0.00983161 -0.0224887 +VERTEX3 299 54.0027 7.02312 85.2707 -0.0173609 -0.00212601 -0.00385293 +VERTEX3 300 52.8618 7.30162 85.3291 -0.0116664 -0.00128202 0.0409096 +VERTEX3 301 53.3034 9.25705 85.1346 -0.0156878 -0.00665091 0.0512054 +VERTEX3 302 53.3246 8.21382 85.0182 -0.0199737 -0.00272629 0.0475818 +VERTEX3 303 53.3511 10.1293 84.9859 -0.0146764 -0.00497814 0.0826852 +VERTEX3 304 53.0751 6.64083 84.946 -0.0086387 0.00520841 0.0732263 +VERTEX3 305 52.4531 3.13363 84.9037 -0.0054137 0.00787717 0.0695493 +VERTEX3 306 52.0876 -0.729835 84.8932 -0.00506627 0.00401312 0.042684 +VERTEX3 307 51.6691 -2.72039 84.876 -0.0174581 0.0117496 0.027297 +VERTEX3 308 51.2524 -4.15717 84.9218 -0.0132013 0.0104503 0.0220666 +VERTEX3 309 50.7469 -5.44227 84.8149 -0.0137358 0.00653209 0.0215345 +VERTEX3 310 50.3575 -6.98886 84.8543 -0.0206327 0.00824173 0.014389 +VERTEX3 311 50.0203 -6.65409 84.8605 -0.0281371 0.0094832 0.027194 +VERTEX3 312 49.3769 -5.18728 84.9156 -0.0316749 0.0074292 0.045931 +VERTEX3 313 48.9674 -3.31332 84.8429 -0.0366243 0.00563657 0.0666582 +VERTEX3 314 48.5642 -3.1944 84.8788 -0.0284662 0.0134263 0.0758405 +VERTEX3 315 48.113 -1.69834 84.8628 -0.0258907 0.00783621 0.086462 +VERTEX3 316 47.7699 -1.08922 84.8297 -0.0218239 0.0111825 0.0950321 +VERTEX3 317 47.0809 0.590193 84.8725 -0.0200756 0.012399 0.112768 +VERTEX3 318 46.5662 1.65136 84.9038 -0.0158028 0.0164964 0.117043 +VERTEX3 319 45.9541 4.42236 84.8937 -0.0222877 0.0182376 0.139208 +VERTEX3 320 44.8932 8.18537 84.9635 -0.0153056 0.0150618 0.192615 +VERTEX3 321 44.0435 10.2362 84.9762 -0.0189525 0.0164869 0.202367 +VERTEX3 322 42.8151 13.4608 84.9007 -0.0172332 0.0147029 0.231354 +VERTEX3 323 41.5681 17.1238 84.929 -0.0154683 0.0163099 0.263481 +VERTEX3 324 40.1139 21.0238 84.8345 -0.0141852 0.0141372 0.306749 +VERTEX3 325 38.7583 24.8025 84.8342 0.00172569 0.0143736 0.327956 +VERTEX3 326 37.4356 -24.1681 85.7029 -0.019998 0.00812255 -0.374158 +VERTEX3 327 39.2963 -20.9927 85.5285 -0.0200141 0.00574686 -0.356102 +VERTEX3 328 41.5697 -16.6116 85.2656 -0.0147631 0.0134988 -0.297473 +VERTEX3 329 43.2697 -13.2526 84.9794 -0.0185111 0.0141511 -0.269271 +VERTEX3 330 44.9139 -9.87548 84.6988 -0.0222706 0.00925746 -0.235988 +VERTEX3 331 46.3226 -7.19546 84.4035 -0.0204193 0.00767958 -0.210845 +VERTEX3 332 47.9028 -3.30338 84.1409 -0.0178905 0.0120887 -0.18323 +VERTEX3 333 49.1575 -0.22443 83.8875 -0.0195495 0.00726769 -0.14888 +VERTEX3 334 50.063 1.78881 83.63 -0.0186805 0.0109868 -0.127296 +VERTEX3 335 51.1095 2.72229 83.3944 -0.0188865 0.0102934 -0.137589 +VERTEX3 336 52.089 4.1104 83.1479 -0.014415 0.00504187 -0.11476 +VERTEX3 337 52.8928 5.96989 82.9416 -0.0110425 0.00360222 -0.0912912 +VERTEX3 338 53.8174 6.44283 82.7694 -0.0175414 0.00429366 -0.0982823 +VERTEX3 339 54.7318 8.69066 82.6567 -0.0117662 0.00214116 -0.0639128 +VERTEX3 340 55.8435 10.6476 82.4755 -0.0121865 0.00416663 -0.0405144 +VERTEX3 341 56.2612 10.8325 82.4013 -0.0110964 0.00370072 -0.0441374 +VERTEX3 342 56.7024 11.7892 82.3315 -0.0055979 -0.0133948 -0.0331851 +VERTEX3 343 57.6866 11.8022 82.2553 -0.00158032 0.00079952 -0.0477242 +VERTEX3 344 58.6795 11.0363 82.3082 -0.00508068 -0.00147263 -0.0478878 +VERTEX3 345 58.983 8.77299 82.0856 -0.00234426 0.0165918 -0.0708636 +VERTEX3 346 59.54 6.69726 82.2711 -0.000337434 0.00525307 -0.0782234 +VERTEX3 347 59.6479 6.94175 82.0872 -0.0139771 0.0155834 -0.0521094 +VERTEX3 348 59.7066 7.56812 81.9907 -0.0162841 0.0030676 -0.0421693 +VERTEX3 349 59.0705 7.3607 81.8676 -0.0125108 0.0041549 0.00499556 +VERTEX3 350 58.1547 8.1463 82.0428 -0.000236845 0.0155917 0.0328911 +VERTEX3 351 58.3742 9.72465 81.9437 -0.0100658 0.00673074 0.0640865 +VERTEX3 352 58.5366 11.4676 81.6841 -0.0158302 -0.00443173 0.0753584 +VERTEX3 353 58.3357 10.7552 81.5708 -0.00921954 -0.00852275 0.0667829 +VERTEX3 354 57.9462 12.3776 81.5456 -0.0116313 -0.0061721 0.102174 +VERTEX3 355 57.4719 6.72108 81.5696 -0.00489903 0.00306231 0.0857961 +VERTEX3 356 57.0042 3.03386 81.4331 -0.00563327 0.00684218 0.0850879 +VERTEX3 357 55.9318 -3.89106 81.3852 -0.00757423 -0.00351823 0.0443944 +VERTEX3 358 55.5448 -5.1348 81.309 -0.017091 0.0103967 0.0151922 +VERTEX3 359 55.3969 -5.71786 81.4475 -0.0181324 0.0078429 0.0216881 +VERTEX3 360 54.9072 -6.07489 81.2901 -0.0186981 0.00694225 0.026996 +VERTEX3 361 54.3739 -7.54876 81.3603 -0.0282531 0.00504636 0.0135742 +VERTEX3 362 54.1162 -6.44117 81.3426 -0.0328252 0.0103752 0.0231513 +VERTEX3 363 53.5158 -5.70248 81.4541 -0.0343553 0.00641285 0.0328333 +VERTEX3 364 53.2078 -4.38531 81.3757 -0.0297427 0.00629165 0.0506519 +VERTEX3 365 52.6304 -3.15572 81.3745 -0.029218 0.013395 0.0623224 +VERTEX3 366 52.2156 -1.88586 81.2298 -0.0249024 0.00709789 0.0790467 +VERTEX3 367 51.684 0.549144 81.2707 -0.0190287 0.0163713 0.115265 +VERTEX3 368 51.1786 0.970172 81.3096 -0.0129235 0.016258 0.0997907 +VERTEX3 369 50.3472 3.49006 81.391 -0.0127545 0.0205797 0.134406 +VERTEX3 370 49.621 6.97447 81.3749 -0.0148 0.0140277 0.167097 +VERTEX3 371 48.7966 10.0152 81.3977 -0.0171923 0.0166634 0.182617 +VERTEX3 372 47.5875 13.4739 81.3188 -0.0169172 0.0183232 0.218401 +VERTEX3 373 46.417 16.9998 81.2888 -0.0105419 0.023786 0.243675 +VERTEX3 374 44.939 21.0269 81.2546 -0.0137017 0.0159969 0.294126 +VERTEX3 375 43.6791 24.505 81.1854 -0.00437607 0.0187288 0.292194 +VERTEX3 376 41.9694 -25.0616 82.1798 -0.0210245 0.00640811 -0.359642 +VERTEX3 377 44.0151 -21.5049 81.9306 -0.0190587 0.0128252 -0.335569 +VERTEX3 378 45.9619 -17.6826 81.6263 -0.0185916 0.0116823 -0.288727 +VERTEX3 379 47.6576 -14.2809 81.3545 -0.025934 0.00997016 -0.268326 +VERTEX3 380 49.4102 -10.3341 81.0027 -0.0220898 0.00647798 -0.230215 +VERTEX3 381 51.0296 -6.20303 80.7 -0.0191605 0.0125317 -0.188826 +VERTEX3 382 52.3145 -2.87997 80.3809 -0.0206769 0.00785875 -0.173006 +VERTEX3 383 53.4673 0.821883 80.1324 -0.0155493 0.0143461 -0.114181 +VERTEX3 384 54.5058 1.82858 79.8804 -0.0162972 0.0114383 -0.124281 +VERTEX3 385 55.3058 3.84338 79.6655 -0.0144553 0.00483867 -0.103282 +VERTEX3 386 56.2798 6.32554 79.3828 -0.00743437 0.00321532 -0.077218 +VERTEX3 387 57.3306 6.14706 79.1968 -0.0156265 0.00266835 -0.0884776 +VERTEX3 388 58.0121 9.68045 79.0663 -0.0102521 0.00578961 -0.0510542 +VERTEX3 389 59.272 9.13286 78.9185 -0.0120131 0.00126654 -0.0605636 +VERTEX3 390 59.6225 10.1016 78.8271 -0.012715 1.00557e-05 -0.0582124 +VERTEX3 391 60.4181 11.9598 78.7649 -0.00950182 -0.0149355 -0.0452632 +VERTEX3 392 61.2478 11.8081 78.6518 -0.00242329 -0.00284914 -0.0498899 +VERTEX3 393 62.9509 9.30021 78.781 0.000996058 -0.00386947 -0.0744884 +VERTEX3 394 63.4689 6.96376 78.6417 0.00126054 -0.00504597 -0.102857 +VERTEX3 395 64.1598 6.02072 78.7593 0.00327825 0.00595128 -0.10115 +VERTEX3 396 64.5278 6.66364 78.5252 -0.00850405 0.0197559 -0.0880397 +VERTEX3 397 64.8457 7.40588 78.3969 -0.0164645 0.00942504 -0.0665152 +VERTEX3 398 64.643 7.3492 78.2605 -0.0173933 0.00716967 -0.0324846 +VERTEX3 399 64.2652 8.69175 78.2816 -0.00462239 0.0144421 0.00182276 +VERTEX3 400 63.2982 9.63682 78.3163 -0.000956363 0.0228255 0.0570765 +VERTEX3 401 63.4008 11.0172 78.1972 -0.00625819 0.0100715 0.0688494 +VERTEX3 402 63.3129 12.7229 78.1096 -0.00877722 0.00556811 0.0859024 +VERTEX3 403 63.0141 12.4707 77.9192 -0.00782167 -0.00958918 0.088706 +VERTEX3 404 62.71 12.0261 77.7899 -0.00998784 -0.00778121 0.0910458 +VERTEX3 405 62.2395 12.9419 77.8394 -0.0029998 -0.0152832 0.122142 +VERTEX3 406 61.6289 9.24046 77.8222 -0.0140223 0.00048557 0.117079 +VERTEX3 407 61.247 6.5719 77.6658 -0.00712804 0.00799585 0.115447 +VERTEX3 408 59.9707 -2.5706 77.7526 -0.0105768 -0.00201727 0.0619532 +VERTEX3 409 59.2641 -6.26597 77.4844 -0.0178507 0.0101053 0.0134197 +VERTEX3 410 59.1501 -6.83826 77.6469 -0.0301172 0.000881152 0.0234388 +VERTEX3 411 58.6923 -5.64551 77.4318 -0.0132619 0.0130986 0.0322892 +VERTEX3 412 58.3319 -5.63062 77.5053 -0.0255062 0.00908024 0.0390824 +VERTEX3 413 58.0218 -4.23643 77.5295 -0.0296689 0.0124983 0.0583346 +VERTEX3 414 57.3359 -5.28592 77.6532 -0.0338433 0.0088794 0.0346287 +VERTEX3 415 56.9738 -2.72338 77.4893 -0.0265633 0.00939769 0.0631637 +VERTEX3 416 56.4299 -2.85433 77.4708 -0.0300276 0.0143169 0.0631664 +VERTEX3 417 55.8671 -0.802812 77.3925 -0.0255527 0.00935022 0.0860371 +VERTEX3 418 55.215 1.85593 77.3817 -0.0170959 0.0131833 0.115508 +VERTEX3 419 54.8615 1.75589 77.4867 -0.0113912 0.0238497 0.102179 +VERTEX3 420 54.0147 5.02775 77.4698 -0.0131635 0.0177119 0.140952 +VERTEX3 421 53.1925 8.64852 77.4829 -0.0228566 0.0176436 0.164332 +VERTEX3 422 51.9769 13.3908 77.4736 -0.0146001 0.0165344 0.207288 +VERTEX3 423 50.6549 17.0366 77.464 -0.0136697 0.0235943 0.234901 +VERTEX3 424 49.4907 20.206 77.3083 -0.0147383 0.0135959 0.261982 +VERTEX3 425 47.9159 25.3051 77.3561 -0.00585661 0.0179526 0.31106 +VERTEX3 426 45.8921 -27.0224 78.2493 -0.028661 0.00947968 -0.381061 +VERTEX3 427 48.2103 -22.0819 77.9499 -0.0182368 0.00799805 -0.314946 +VERTEX3 428 50.3988 -17.652 77.6974 -0.0291636 0.0103978 -0.283802 +VERTEX3 429 51.8576 -14.5857 77.3425 -0.0237484 0.00572123 -0.252586 +VERTEX3 430 53.8299 -8.95697 76.9689 -0.0197983 0.012415 -0.20116 +VERTEX3 431 55.1967 -5.56211 76.6667 -0.0217975 0.00800023 -0.173298 +VERTEX3 432 56.384 -3.1187 76.4018 -0.0183685 0.01166 -0.156683 +VERTEX3 433 57.3447 -1.67049 76.167 -0.0209109 0.0118942 -0.158124 +VERTEX3 434 58.4074 1.42038 75.9104 -0.0165197 0.00450599 -0.11794 +VERTEX3 435 59.2853 4.4271 75.7066 -0.00656003 0.00621908 -0.0963727 +VERTEX3 436 60.4693 5.41208 75.4647 -0.0137325 0.00273594 -0.0956792 +VERTEX3 437 61.1156 9.12959 75.2207 -0.0110223 0.00526189 -0.0611246 +VERTEX3 438 62.3196 7.701 75.0428 -0.0137894 0.00236249 -0.0882388 +VERTEX3 439 62.6771 10.5194 74.9931 -0.0143716 -0.00142506 -0.056913 +VERTEX3 440 63.3276 13.4347 74.7971 -0.00912592 -0.0205888 -0.0391359 +VERTEX3 441 64.439 13.2635 74.7299 -0.00223452 -0.0108832 -0.0490566 +VERTEX3 442 66.4676 10.0728 74.9514 0.00344393 -0.00708555 -0.0963595 +VERTEX3 443 67.173 7.09337 74.8281 0.00496153 0.0127804 -0.121559 +VERTEX3 444 68.1252 4.34066 74.9595 0.0191388 0.00531332 -0.148547 +VERTEX3 445 68.94 5.07015 74.6995 -0.0027131 0.0226251 -0.122104 +VERTEX3 446 69.4435 7.30718 74.5579 -0.016048 0.0156949 -0.0956836 +VERTEX3 447 69.5651 6.25942 74.4611 -0.0185344 0.00888102 -0.0749965 +VERTEX3 448 69.6689 8.22666 74.3786 -0.00873363 0.0137603 -0.0414374 +VERTEX3 449 69.1043 9.39205 74.2189 -0.001218 0.0147728 0.0102962 +VERTEX3 450 68.4241 11.237 74.1527 -0.0210666 0.0223965 0.0697487 +VERTEX3 451 68.2765 13.6974 74.0308 -0.00345937 0.0143825 0.0836464 +VERTEX3 452 68.0955 15.1976 74.0536 -0.0147625 0.00592209 0.0987413 +VERTEX3 453 67.7231 15.97 73.9494 -0.00649374 0.00328026 0.108612 +VERTEX3 454 67.242 15.8636 73.8615 -0.00699582 -0.0101478 0.106043 +VERTEX3 455 66.7489 14.4718 73.767 -0.00675332 -0.0143118 0.110757 +VERTEX3 456 65.9155 16.441 73.765 -0.00543522 -0.0147423 0.142279 +VERTEX3 457 65.4664 11.7671 73.7269 -0.015879 -0.000361369 0.13612 +VERTEX3 458 64.7075 6.73981 73.5793 -0.00717743 0.00802261 0.13491 +VERTEX3 459 63.3232 -1.53533 73.5323 -0.0119245 0.00415147 0.0888973 +VERTEX3 460 63.332 -3.50054 73.2627 -0.0252262 0.0165114 0.0582553 +VERTEX3 461 63.0084 -2.70223 73.4545 -0.02263 0.0170142 0.0600761 +VERTEX3 462 62.511 -3.42772 73.2389 -0.0277893 0.0154091 0.0558396 +VERTEX3 463 61.8677 -3.72763 73.3972 -0.024564 0.00937038 0.0600196 +VERTEX3 464 61.3435 -1.10094 73.2903 -0.0251617 0.0114812 0.0935594 +VERTEX3 465 60.6994 -3.99231 73.5258 -0.0350107 0.0127011 0.0565168 +VERTEX3 466 60.2898 -1.30918 73.2557 -0.0245449 0.016124 0.0908228 +VERTEX3 467 59.6986 -1.97127 73.3598 -0.0302134 0.0154029 0.077648 +VERTEX3 468 59.1139 1.59609 73.1751 -0.024592 0.0167363 0.113077 +VERTEX3 469 58.5795 2.41601 73.2331 -0.0185944 0.0106954 0.104467 +VERTEX3 470 57.9173 4.92057 73.4016 -0.0235468 0.018602 0.14382 +VERTEX3 471 57.1765 6.88811 73.3298 -0.01219 0.0209868 0.146249 +VERTEX3 472 55.9428 11.8582 73.3021 -0.0144801 0.0171955 0.179662 +VERTEX3 473 54.9287 15.6549 73.2984 -0.0163535 0.0172499 0.209187 +VERTEX3 474 53.5001 19.7125 73.2763 -0.0112309 0.0224411 0.246531 +VERTEX3 475 51.8058 24.6228 73.2482 -0.0156025 0.0137502 0.273545 +VERTEX3 476 49.8691 -26.9123 74.0291 -0.0264362 0.0136142 -0.335365 +VERTEX3 477 52.276 -21.6791 73.766 -0.0288048 0.0098075 -0.295135 +VERTEX3 478 54.0818 -17.858 73.4612 -0.0251528 0.00613289 -0.263375 +VERTEX3 479 55.9046 -13.234 73.0435 -0.0219545 0.0106667 -0.238822 +VERTEX3 480 57.4574 -9.00501 72.6966 -0.0237749 0.00998082 -0.187569 +VERTEX3 481 58.7003 -6.95292 72.3707 -0.0234198 0.0083984 -0.188185 +VERTEX3 482 59.9235 -3.72211 72.158 -0.0192912 0.0131822 -0.162399 +VERTEX3 483 60.8814 -1.74465 71.879 -0.0223822 0.00249604 -0.145318 +VERTEX3 484 61.9153 2.29054 71.6609 -0.00668479 0.0103825 -0.110035 +VERTEX3 485 63.1237 2.89165 71.4348 -0.0176539 0.00462231 -0.125802 +VERTEX3 486 63.9924 6.49247 71.2674 -0.00977598 0.00470964 -0.0935598 +VERTEX3 487 65.2827 5.55641 70.9849 -0.0147603 0.00577535 -0.124225 +VERTEX3 488 65.4534 9.12334 70.8798 -0.0145269 -0.00320107 -0.0779135 +VERTEX3 489 65.9674 12.4312 70.7255 -0.0132076 -0.0245447 -0.060476 +VERTEX3 490 67.5953 11.7244 70.6305 -0.00314398 -0.0131012 -0.0754407 +VERTEX3 491 69.5222 9.05291 70.7949 0.00419939 -0.0111996 -0.117712 +VERTEX3 492 70.3114 5.18692 70.6436 0.0198126 -0.000336537 -0.15383 +VERTEX3 493 71.5844 3.71806 70.9162 0.0254219 0.00346829 -0.16721 +VERTEX3 494 72.547 3.23532 70.5916 0.00603258 0.0237559 -0.155141 +VERTEX3 495 73.4197 6.11513 70.5261 -0.0144478 0.0209778 -0.129998 +VERTEX3 496 73.9081 4.9484 70.3371 -0.0150833 0.00774103 -0.119647 +VERTEX3 497 74.485 7.15776 70.2901 -0.0121846 0.0114154 -0.0707053 +VERTEX3 498 74.0112 8.59563 70.0284 -0.00114316 0.00839202 -0.0324119 +VERTEX3 499 73.8878 10.2177 69.9394 -0.0207945 0.0110628 0.00851152 +VERTEX3 500 72.9021 12.6687 69.6664 -0.0198636 0.0155312 0.0672125 +VERTEX3 501 72.8187 15.9078 69.6023 -0.0170608 0.0182499 0.0903465 +VERTEX3 502 72.3862 17.1435 69.5154 -0.003253 0.00655729 0.109385 +VERTEX3 503 72.1064 19.3584 69.6099 -0.0169192 0.00222569 0.12361 +VERTEX3 504 71.4706 19.5397 69.5581 -0.00619347 0.000910415 0.131234 +VERTEX3 505 70.7138 18.2478 69.4385 -0.0106572 -0.00994795 0.128194 +VERTEX3 506 70.2678 17.6728 69.4477 -0.00897994 -0.0144248 0.12647 +VERTEX3 507 69.3305 20.9445 69.3983 -0.016738 -0.00534117 0.16626 +VERTEX3 508 68.6328 13.7978 69.2971 -0.0181947 -4.58686e-05 0.151825 +VERTEX3 509 67.6505 6.65243 69.1586 -0.00498227 0.00584294 0.13429 +VERTEX3 510 67.0301 0.0713851 69.1736 -0.015661 0.00382371 0.111357 +VERTEX3 511 66.7591 -0.214575 68.7331 -0.0317461 0.0242646 0.103667 +VERTEX3 512 66.4387 -0.191031 68.9652 -0.0290795 0.0239169 0.0891438 +VERTEX3 513 65.7179 -2.69549 68.7582 -0.0224177 0.0234266 0.0752196 +VERTEX3 514 64.9126 -5.43215 69.0302 -0.0312073 0.0130684 0.0574907 +VERTEX3 515 64.534 -1.2359 68.8544 -0.0281637 0.0147902 0.101471 +VERTEX3 516 63.7712 -4.49547 68.9778 -0.0362755 0.0120358 0.0465539 +VERTEX3 517 63.3709 -1.58647 68.8414 -0.0204645 0.016708 0.0991738 +VERTEX3 518 62.8038 -1.84308 68.9164 -0.0274236 0.0157835 0.0771993 +VERTEX3 519 62.1497 2.39575 68.8165 -0.0238642 0.0174438 0.109651 +VERTEX3 520 61.7167 2.44126 68.8668 -0.0191361 0.0133861 0.106758 +VERTEX3 521 60.4333 8.09033 68.9003 -0.0187312 0.0104871 0.16503 +VERTEX3 522 59.8168 9.77281 68.9017 -0.0168229 0.0201278 0.153985 +VERTEX3 523 58.3034 14.9317 68.8821 -0.0210837 0.0232989 0.201864 +VERTEX3 524 57.1085 18.5324 68.8642 -0.0185215 0.0162721 0.219102 +VERTEX3 525 55.7025 20.6617 68.9418 -0.016362 0.0117448 0.216682 +VERTEX3 526 53.4525 -23.8672 69.6497 -0.0254921 0.00896929 -0.278487 +VERTEX3 527 55.5557 -21.3724 69.2384 -0.0256016 0.00750632 -0.268885 +VERTEX3 528 57.1827 -17.8436 68.9897 -0.0232625 0.00646636 -0.27328 +VERTEX3 529 59.3078 -13.1385 68.6078 -0.0237676 0.0099175 -0.220816 +VERTEX3 530 60.7696 -9.51791 68.2069 -0.0251335 0.0121282 -0.192675 +VERTEX3 531 62.4274 -5.10762 67.8136 -0.0164664 0.0142004 -0.157319 +VERTEX3 532 63.2869 -4.23786 67.5856 -0.0239037 0.0018702 -0.158805 +VERTEX3 533 64.4045 1.21919 67.3233 -0.00856687 0.0119505 -0.109921 +VERTEX3 534 65.3899 -0.0223879 67.1478 -0.0160778 0.00572351 -0.134413 +VERTEX3 535 66.2996 4.99242 66.8729 -0.0113177 0.00566002 -0.101125 +VERTEX3 536 67.6211 4.49741 66.7139 -0.0110988 0.00594051 -0.132086 +VERTEX3 537 67.9704 7.20759 66.5075 -0.0141954 -0.00574413 -0.0995988 +VERTEX3 538 68.3642 10.0364 66.2823 -0.012281 -0.0273209 -0.0932424 +VERTEX3 539 70.0281 9.96763 66.226 -0.0018921 -0.0111663 -0.116995 +VERTEX3 540 72.1347 6.67781 66.4278 0.00485565 -0.0136738 -0.150651 +VERTEX3 541 73.0287 2.91844 66.0916 0.0264976 0.00400386 -0.177941 +VERTEX3 542 74.3023 2.37699 66.5287 0.0331381 0.00277734 -0.189925 +VERTEX3 543 75.2037 4.88287 66.2073 0.00715625 0.0274876 -0.179612 +VERTEX3 544 77.0117 3.77966 66.1815 -0.0105626 0.0242853 -0.172339 +VERTEX3 545 77.6488 4.01919 65.9045 -0.00328614 0.00733363 -0.174923 +VERTEX3 546 78.6413 5.48303 66.0191 -0.0149087 0.0113116 -0.110616 +VERTEX3 547 78.368 6.80824 65.7354 -0.00448093 0.00170976 -0.0784174 +VERTEX3 548 78.6828 8.54995 65.625 -0.0206747 0.000929625 -0.0390994 +VERTEX3 549 78.0498 11.3843 65.3666 -0.0140676 0.0134489 0.00965939 +VERTEX3 550 77.2744 14.1655 64.9978 -0.0305618 0.0334602 0.070167 +VERTEX3 551 77.0737 17.7293 65.0039 -0.0195533 0.0127829 0.0987012 +VERTEX3 552 76.7113 20.6389 64.9577 -0.0130705 0.0116092 0.113114 +VERTEX3 553 76.043 21.4763 64.884 -0.00436681 -0.00143108 0.134442 +VERTEX3 554 75.5439 22.6771 64.9367 -0.0220706 -0.00549649 0.140533 +VERTEX3 555 74.4289 22.3423 64.8422 -0.0055472 -0.00338694 0.150518 +VERTEX3 556 73.8 21.4641 64.7314 -0.0157799 -0.00623357 0.152662 +VERTEX3 557 73.3615 18.6491 64.8823 -0.011394 -0.0128741 0.140426 +VERTEX3 558 72.1731 22.3335 64.6344 -0.0121934 -0.00789981 0.181131 +VERTEX3 559 71.5097 13.5287 64.5201 -0.00430385 0.00469868 0.148417 +VERTEX3 560 70.6922 8.10643 64.4697 -0.00312417 0.00438471 0.139508 +VERTEX3 561 70.3688 4.54558 64.3419 -0.014973 0.0127616 0.137704 +VERTEX3 562 69.2697 4.18345 63.8837 -0.0380339 0.0319302 0.156718 +VERTEX3 563 69.1765 1.41171 64.2264 -0.026407 0.026275 0.125302 +VERTEX3 564 68.299 -2.52475 63.9873 -0.0197439 0.0277398 0.103419 +VERTEX3 565 67.5973 -1.82928 64.2044 -0.0340759 0.0155011 0.102751 +VERTEX3 566 67.3759 -1.87231 64.1446 -0.0316334 0.0153528 0.10037 +VERTEX3 567 66.5058 -5.02009 64.3706 -0.0370282 0.0158515 0.059691 +VERTEX3 568 66.1212 0.136473 64.1429 -0.0217427 0.0151685 0.101932 +VERTEX3 569 65.522 -1.04537 64.2909 -0.0307658 0.0169898 0.0734802 +VERTEX3 570 64.8059 2.40621 64.1795 -0.0220424 0.0155618 0.104646 +VERTEX3 571 64.0023 5.47544 64.2078 -0.0182753 0.0239214 0.131166 +VERTEX3 572 62.8848 9.17477 64.2525 -0.0230451 0.0110014 0.145094 +VERTEX3 573 61.7298 13.125 64.2082 -0.0182305 0.0213898 0.178673 +VERTEX3 574 60.7473 15.0814 64.1768 -0.0220088 0.00758102 0.175674 +VERTEX3 575 59.5618 16.149 64.3019 -0.0274041 0.014593 0.160044 +VERTEX3 576 57.0182 -21.0478 64.8053 -0.0211283 0.00914641 -0.230013 +VERTEX3 577 58.587 -20.1162 64.5406 -0.0213846 0.00754474 -0.254278 +VERTEX3 578 60.2913 -17.4132 64.2049 -0.0257598 0.0114625 -0.246807 +VERTEX3 579 62.5821 -11.7067 63.8441 -0.0187325 0.0188071 -0.184893 +VERTEX3 580 63.9633 -9.2356 63.4528 -0.0240968 0.0137532 -0.194062 +VERTEX3 581 65.1371 -6.21548 63.1538 -0.0214582 0.00561087 -0.146091 +VERTEX3 582 66.3709 -1.83556 62.7715 -0.0121062 0.0143219 -0.127558 +VERTEX3 583 67.4129 -2.57782 62.6392 -0.0204508 0.00766102 -0.151933 +VERTEX3 584 68.2319 2.34781 62.3668 -0.013405 0.00908074 -0.116246 +VERTEX3 585 69.4642 1.17755 62.2102 -0.0123348 0.00529402 -0.147832 +VERTEX3 586 70.1503 4.31575 62.0396 -0.0180162 -0.0019453 -0.135434 +VERTEX3 587 70.8228 6.58046 61.8574 -0.010316 -0.0281312 -0.128768 +VERTEX3 588 71.8267 7.59569 61.5587 -0.00251341 -0.0168587 -0.13834 +VERTEX3 589 73.8905 5.05312 61.6631 0.00630761 -0.0188925 -0.172777 +VERTEX3 590 75.044 0.726053 61.2899 0.0286976 0.0138554 -0.199511 +VERTEX3 591 76.4597 -2.09378 61.8458 0.0459106 -0.00818757 -0.234268 +VERTEX3 592 77.6904 1.05987 61.5977 0.0222279 0.0262248 -0.209293 +VERTEX3 593 79.635 0.338552 61.6617 -0.00445757 0.0228081 -0.215563 +VERTEX3 594 80.6909 0.152197 61.5177 -0.00391415 0.0175093 -0.213233 +VERTEX3 595 81.9552 2.65621 61.5252 -0.0160377 0.0119054 -0.158546 +VERTEX3 596 82.2938 3.44608 61.3057 -0.00288757 -0.00391636 -0.129754 +VERTEX3 597 82.8194 5.74513 61.1493 -0.0159921 -0.00811412 -0.10755 +VERTEX3 598 82.5207 9.97892 60.8498 -0.0129034 0.00518367 -0.0333057 +VERTEX3 599 82.2119 12.1143 60.5216 -0.0272962 0.0126568 0.0173892 +VERTEX3 600 81.2849 15.723 60.0519 -0.0496055 0.00233739 0.0909591 +VERTEX3 601 81.2085 19.1877 60.0782 -0.0295108 0.0227628 0.109213 +VERTEX3 602 80.4634 21.9961 60.1543 -0.0179702 0.00742205 0.125145 +VERTEX3 603 79.9762 25.3812 60.1483 -0.01404 0.00702298 0.142076 +VERTEX3 604 79.0695 26.2525 59.984 -0.00567697 -0.00942734 0.158199 +VERTEX3 605 78.3156 26.2257 60.0379 -0.0271245 -0.00983481 0.159773 +VERTEX3 606 77.2975 26.4239 60.0444 -0.00519576 -0.00687188 0.170469 +VERTEX3 607 76.4604 23.8726 59.8059 -0.0110877 -0.00856797 0.165667 +VERTEX3 608 75.8459 22.248 59.9637 -0.00203011 -0.0131179 0.154363 +VERTEX3 609 74.6143 24.1761 59.715 -0.00651044 -0.00431777 0.190519 +VERTEX3 610 73.8821 15.4076 59.6353 -0.00387742 0.00568921 0.158144 +VERTEX3 611 73.1041 9.03693 59.6121 -0.00195893 0.00305752 0.148808 +VERTEX3 612 73.0668 2.39615 59.3603 -0.0173103 0.00852702 0.147059 +VERTEX3 613 72.0262 1.06787 59.018 -0.0380871 0.0280999 0.138365 +VERTEX3 614 71.5494 -1.00855 59.2986 -0.0486662 0.0174049 0.131034 +VERTEX3 615 70.5525 0.584952 58.9933 -0.0481738 0.0278705 0.136642 +VERTEX3 616 70.0018 -0.433854 59.2301 -0.0271072 0.0214773 0.139175 +VERTEX3 617 69.6029 0.117763 59.1727 -0.0370342 0.0150098 0.12934 +VERTEX3 618 68.9342 -3.16959 59.457 -0.0340436 0.0165674 0.0866023 +VERTEX3 619 68.3952 0.650422 59.2777 -0.0262818 0.0206145 0.114213 +VERTEX3 620 67.7347 0.158112 59.3949 -0.0291606 0.0217105 0.0977045 +VERTEX3 621 66.4882 6.29146 59.2342 -0.0248595 0.0228696 0.144311 +VERTEX3 622 65.8141 8.56539 59.3143 -0.0186248 0.0169654 0.145585 +VERTEX3 623 64.9461 11.2379 59.3602 -0.0233613 0.00897686 0.158008 +VERTEX3 624 63.3163 15.8112 59.3773 -0.0184729 0.0201146 0.190482 +VERTEX3 625 61.7714 20.0803 59.1756 -0.0207913 0.0160139 0.209711 +VERTEX3 626 59.0775 -26.123 60.1316 -0.022467 0.00597761 -0.28838 +VERTEX3 627 61.1362 -21.7498 59.7594 -0.0290432 0.0127289 -0.266368 +VERTEX3 628 63.5841 -15.5999 59.2024 -0.0217032 0.0169284 -0.202217 +VERTEX3 629 65.0603 -13.3881 58.894 -0.0247724 0.0146361 -0.214769 +VERTEX3 630 66.2009 -10.3298 58.7073 -0.0234632 0.00532806 -0.183126 +VERTEX3 631 67.7717 -5.70785 58.2364 -0.022651 0.0106468 -0.164964 +VERTEX3 632 68.9052 -4.59089 57.9265 -0.0191271 0.0101303 -0.150208 +VERTEX3 633 69.9215 -0.00118403 57.7501 -0.016873 0.0125514 -0.136438 +VERTEX3 634 71.2978 -0.624354 57.3862 -0.0144851 0.00350512 -0.154454 +VERTEX3 635 71.9675 -0.277563 57.3249 -0.0304416 0.00557193 -0.17481 +VERTEX3 636 72.325 3.60756 57.0739 -0.015984 -0.026738 -0.149086 +VERTEX3 637 73.476 3.25872 56.6898 -0.00445076 -0.0108853 -0.184118 +VERTEX3 638 75.3636 0.412476 56.7188 0.00410794 -0.021358 -0.229584 +VERTEX3 639 76.4284 -1.37913 56.4738 0.0258366 0.00181339 -0.217454 +VERTEX3 640 78.4093 -4.26884 57.0099 0.0480991 -0.00804896 -0.246185 +VERTEX3 641 79.679 -1.58055 56.7824 0.0323394 0.0329524 -0.230975 +VERTEX3 642 81.4553 -1.61343 56.8832 0.00358333 0.0196743 -0.251662 +VERTEX3 643 82.7457 -3.62521 56.7107 0.0002787 0.0291731 -0.255105 +VERTEX3 644 84.5576 -1.84396 56.8836 -0.0158184 0.0127981 -0.223578 +VERTEX3 645 85.2334 -0.103952 56.5932 -0.00279365 -0.00585068 -0.180698 +VERTEX3 646 86.4118 2.64203 56.4817 -0.0142534 -0.0144041 -0.155635 +VERTEX3 647 86.3337 7.44155 56.116 -0.00578343 0.000395855 -0.0893416 +VERTEX3 648 86.5562 9.41025 55.8172 -0.0211082 -0.00535714 -0.0397055 +VERTEX3 649 85.9882 13.1036 55.517 -0.0393055 -0.0103625 0.0305467 +VERTEX3 650 85.2456 16.9952 55.0394 -0.0653024 -0.00489155 0.0823954 +VERTEX3 651 84.7615 21.2367 55.0361 -0.044144 0.00297867 0.120424 +VERTEX3 652 84.2599 23.8285 54.9792 -0.028836 0.016039 0.144811 +VERTEX3 653 83.1138 26.2779 55.136 -0.0140803 0.000443527 0.148413 +VERTEX3 654 82.6075 30.5563 55.1196 -0.0117488 0.00196197 0.167341 +VERTEX3 655 81.4227 31.6188 54.9825 -0.0063561 -0.0149053 0.182333 +VERTEX3 656 80.6683 31.54 54.8549 -0.0271707 -0.00831737 0.182721 +VERTEX3 657 79.469 30.0633 54.9229 -0.00185389 -0.00722509 0.191852 +VERTEX3 658 78.5274 26.1463 54.6882 -0.0083664 -0.00606912 0.179345 +VERTEX3 659 77.8452 21.3982 54.7913 -0.00728453 -0.00881074 0.164337 +VERTEX3 660 76.8418 23.1384 54.5572 0.00103212 -0.00609967 0.200877 +VERTEX3 661 76.0389 14.0178 54.4937 0.0087243 0.00734398 0.160755 +VERTEX3 662 75.4546 15.3479 54.4672 -0.00424914 0.00390731 0.190033 +VERTEX3 663 75.2141 1.85736 54.2239 -0.0178186 0.00611395 0.152217 +VERTEX3 664 74.0611 -3.87672 54.0219 -0.0319787 0.0204804 0.0843422 +VERTEX3 665 73.7649 0.872922 54.1695 -0.0417122 0.0249753 0.170759 +VERTEX3 666 72.5544 0.527322 53.8358 -0.0412049 0.0308947 0.157653 +VERTEX3 667 71.9336 0.489995 53.9602 -0.024856 0.0232993 0.152055 +VERTEX3 668 71.6147 0.0746133 54.0787 -0.0344393 0.013569 0.132328 +VERTEX3 669 70.8036 -2.30255 54.322 -0.0357963 0.0200361 0.10007 +VERTEX3 670 70.2642 0.793434 54.219 -0.0303896 0.022171 0.108532 +VERTEX3 671 69.4453 2.04554 54.323 -0.0296545 0.0258137 0.118342 +VERTEX3 672 68.1272 9.33041 54.1366 -0.0210678 0.0277584 0.165877 +VERTEX3 673 67.5531 10.8511 54.2853 -0.0154632 0.011338 0.168723 +VERTEX3 674 66.2142 15.5656 54.2038 -0.0150835 0.021151 0.186656 +VERTEX3 675 64.7788 20.4513 54.0834 -0.0142432 0.0182531 0.217196 +VERTEX3 676 61.6644 -27.8617 55.0661 -0.0302867 0.0101545 -0.294392 +VERTEX3 677 64.0967 -21.2778 54.5198 -0.0271138 0.0139832 -0.236316 +VERTEX3 678 65.9291 -17.5881 54.2108 -0.0249015 0.0110091 -0.227902 +VERTEX3 679 67.0632 -14.3148 53.9177 -0.0260127 0.0126639 -0.20145 +VERTEX3 680 68.8231 -8.90158 53.496 -0.0235066 0.00917395 -0.175062 +VERTEX3 681 70.2181 -4.49989 53.0455 -0.00777254 0.0108478 -0.120554 +VERTEX3 682 70.9546 -2.53736 52.7953 -0.01751 0.00772758 -0.132115 +VERTEX3 683 72.2727 -3.80811 52.6122 -0.017709 0.00646656 -0.173109 +VERTEX3 684 72.9709 -2.26777 52.462 -0.0323484 0.00365506 -0.184364 +VERTEX3 685 73.443 -0.00666649 52.1329 -0.0233338 -0.0205968 -0.170622 +VERTEX3 686 74.7822 -1.13646 51.7919 -0.0163444 -0.00592588 -0.232203 +VERTEX3 687 76.819 0.244013 51.681 0.00870999 -0.022023 -0.229575 +VERTEX3 688 77.5416 1.23527 51.4647 0.0191525 0.00635124 -0.240481 +VERTEX3 689 79.539 -4.73134 51.9025 0.0513422 -0.012826 -0.262398 +VERTEX3 690 81.0333 -3.55678 51.7264 0.0400741 0.0353231 -0.248539 +VERTEX3 691 82.9526 -4.44361 52.0851 0.0119945 0.0317988 -0.262551 +VERTEX3 692 83.959 -5.42022 51.6595 -0.00350701 0.0423192 -0.29258 +VERTEX3 693 86.3688 -5.35618 51.9621 -0.0124104 0.013657 -0.268545 +VERTEX3 694 87.2069 -1.75126 51.6198 -0.000208912 -0.00936682 -0.228211 +VERTEX3 695 88.6518 1.58732 51.4324 -0.0168626 -0.01704 -0.16986 +VERTEX3 696 89.2306 4.18682 51.1844 -0.00347875 -0.0118634 -0.139061 +VERTEX3 697 89.8863 6.4037 50.9373 -0.0108058 -0.0197895 -0.0991312 +VERTEX3 698 89.9117 9.92413 50.6316 -0.0233607 -0.0226689 -0.0419584 +VERTEX3 699 89.7141 13.6821 50.236 -0.0509179 -0.0191863 0.0240457 +VERTEX3 700 88.7268 17.6031 49.7715 -0.0573131 -0.0200124 0.100447 +VERTEX3 701 88.176 22.2026 49.7451 -0.0476565 -0.00577339 0.125869 +VERTEX3 702 87.0895 26.0313 49.7974 -0.0311996 -0.00114507 0.149417 +VERTEX3 703 86.4875 28.4075 49.7758 -0.0243294 0.0111182 0.174384 +VERTEX3 704 85.2928 30.6089 49.9998 -0.0112716 -0.00533961 0.173596 +VERTEX3 705 84.2316 32.7021 49.8069 -0.00554105 -0.00291513 0.179217 +VERTEX3 706 83.4494 33.7355 49.7011 -0.00506101 -0.0187771 0.204932 +VERTEX3 707 82.4178 35.8213 49.4495 -0.0253326 -0.010242 0.200114 +VERTEX3 708 81.1177 32.9756 49.5875 -0.0069687 -0.0117909 0.210594 +VERTEX3 709 80.3438 28.4174 49.3098 -0.00429908 -0.00701249 0.191519 +VERTEX3 710 80.1213 24.8159 49.5895 -0.00190644 -0.0109947 0.181382 +VERTEX3 711 78.7289 23.5946 49.239 0.00816397 -0.012609 0.211648 +VERTEX3 712 77.9394 17.1219 49.2002 0.00779781 0.00900162 0.183332 +VERTEX3 713 77.3238 14.3804 49.1862 -0.00274127 0.00206134 0.187515 +VERTEX3 714 77.2672 2.88997 48.7895 -0.0185098 0.00801291 0.16012 +VERTEX3 715 76.2745 -3.26535 48.6884 -0.0338626 0.019794 0.0847692 +VERTEX3 716 75.5774 1.44698 48.7045 -0.050735 0.0291475 0.188527 +VERTEX3 717 74.2441 1.16782 48.3381 -0.041669 0.0412639 0.176864 +VERTEX3 718 73.4907 0.148022 48.7587 -0.0235938 0.0208275 0.165006 +VERTEX3 719 72.7997 1.5401 48.7549 -0.0354551 0.0224181 0.156335 +VERTEX3 720 72.2946 -1.02371 49.1278 -0.0317287 0.0213259 0.134221 +VERTEX3 721 71.6542 1.80545 48.9271 -0.0341099 0.030297 0.117687 +VERTEX3 722 70.484 5.93975 49.073 -0.0293064 0.0327116 0.157811 +VERTEX3 723 69.1132 12.559 48.8584 -0.0152093 0.0372826 0.191493 +VERTEX3 724 68.7582 14.7609 48.8935 -0.0155415 0.021025 0.178775 +VERTEX3 725 67.1879 21.2275 48.804 -0.0166714 0.0218242 0.236231 +VERTEX3 726 64.3485 -28.7828 49.8313 -0.021826 0.0153218 -0.279644 +VERTEX3 727 66.5123 -22.3704 49.4143 -0.0256503 0.0117715 -0.250336 +VERTEX3 728 67.9183 -17.8878 49.0274 -0.0349258 0.0202727 -0.216996 +VERTEX3 729 69.1616 -13.28 48.678 -0.0320404 0.00757678 -0.205966 +VERTEX3 730 71.0932 -8.591 48.135 -0.0148272 0.0126036 -0.144099 +VERTEX3 731 71.8148 -4.83797 47.8617 -0.021217 0.00702918 -0.142254 +VERTEX3 732 72.767 -6.11825 47.5371 -0.0133301 0.00220335 -0.190372 +VERTEX3 733 73.3443 -6.51402 47.5871 -0.0374845 0.00756988 -0.21513 +VERTEX3 734 74.2691 -1.82092 47.0645 -0.0332907 -0.0136747 -0.195262 +VERTEX3 735 75.2537 -3.09486 46.6236 -0.018922 -0.00833399 -0.235782 +VERTEX3 736 77.6551 -3.74452 46.4503 0.00914821 -0.0232189 -0.260852 +VERTEX3 737 78.6873 -3.75921 46.1817 0.0123879 0.00362384 -0.249844 +VERTEX3 738 80.1767 -7.29744 46.7122 0.0570214 -0.0184548 -0.282695 +VERTEX3 739 81.5864 -4.91052 46.477 0.0466541 0.04541 -0.251544 +VERTEX3 740 83.5286 -6.8539 46.9192 0.0200306 0.0384633 -0.279398 +VERTEX3 741 84.4976 -9.2165 46.7503 -0.021048 0.0599997 -0.325122 +VERTEX3 742 87.5451 -6.86467 46.8733 -0.00845063 0.0164523 -0.280938 +VERTEX3 743 88.5471 -4.98959 46.6215 0.000902497 -0.0118972 -0.272579 +VERTEX3 744 90.4677 -1.25128 46.3998 -0.01494 -0.0205508 -0.217845 +VERTEX3 745 91.4563 -0.168826 45.9984 0.000449029 -0.0272835 -0.19124 +VERTEX3 746 92.5544 3.07436 45.7499 0.000482062 -0.0333236 -0.158464 +VERTEX3 747 92.9546 6.16456 45.5195 -0.00557253 -0.0312157 -0.110376 +VERTEX3 748 93.2565 10.7866 45.1652 -0.036139 -0.0320056 -0.0385905 +VERTEX3 749 93.0126 14.358 44.7575 -0.0378294 -0.0329598 0.0309347 +VERTEX3 750 91.8962 18.3813 44.3939 -0.0417227 -0.0375177 0.109074 +VERTEX3 751 91.1509 23.0409 44.2863 -0.0316845 -0.0208533 0.135708 +VERTEX3 752 89.9635 26.7624 44.3448 -0.0344164 -0.00677082 0.156769 +VERTEX3 753 88.7134 31.1812 44.5134 -0.0228679 -0.00272198 0.173755 +VERTEX3 754 88.0237 34.1775 44.3158 -0.0190899 0.00837531 0.200118 +VERTEX3 755 86.8154 36.8346 44.6536 -0.00680533 -0.00701978 0.199318 +VERTEX3 756 85.8033 36.1306 44.4461 -0.00295266 -0.00885419 0.196774 +VERTEX3 757 84.9081 37.6388 44.2965 -0.00402514 -0.02127 0.221382 +VERTEX3 758 83.9733 37.3668 43.9811 -0.0241206 -0.00980375 0.218354 +VERTEX3 759 82.7706 37.7459 44.0898 -0.0024727 -0.0164722 0.227421 +VERTEX3 760 81.8628 32.4158 43.8135 -0.00284029 -0.00766301 0.207483 +VERTEX3 761 81.573 28.9208 44.0455 0.00421434 -0.0147532 0.202206 +VERTEX3 762 79.9551 30.6401 43.8562 -0.00260638 0.00297771 0.238728 +VERTEX3 763 79.2023 25.4387 43.8535 -0.011235 0.0117529 0.219517 +VERTEX3 764 79.1609 17.1392 43.7901 -0.00187428 0.00144287 0.196959 +VERTEX3 765 78.5854 3.77956 43.3984 -0.0182481 0.00517545 0.171316 +VERTEX3 766 77.7226 -0.386012 42.8536 -0.0429081 0.0356231 0.171533 +VERTEX3 767 76.7207 2.42442 43.0388 -0.0490994 0.0457613 0.217845 +VERTEX3 768 75.168 2.24544 42.9077 -0.0478442 0.0543478 0.203527 +VERTEX3 769 74.3495 1.34438 43.2648 -0.0254237 0.0251692 0.189184 +VERTEX3 770 73.6622 1.88617 43.3629 -0.0271375 0.0284353 0.177605 +VERTEX3 771 72.8999 2.1778 43.6404 -0.0236098 0.0248541 0.172921 +VERTEX3 772 72.5773 3.88452 43.4588 -0.0395586 0.0398246 0.142885 +VERTEX3 773 71.1431 9.87463 43.5642 -0.0219303 0.0383658 0.181876 +VERTEX3 774 69.9124 16.8523 43.358 -0.00654434 0.024109 0.218046 +VERTEX3 775 69.8098 19.0899 43.4737 -0.0187744 0.017472 0.207215 +VERTEX3 776 66.6654 -28.2559 44.401 -0.0205661 0.00874708 -0.259159 +VERTEX3 777 67.4084 -24.6081 44.1218 -0.0399563 0.0119249 -0.257004 +VERTEX3 778 69.0013 -18.3261 43.7172 -0.0439058 0.00866503 -0.229007 +VERTEX3 779 71.0994 -12.811 43.1487 -0.038899 0.0138586 -0.193363 +VERTEX3 780 71.7491 -9.63101 42.8928 -0.0358887 0.0133382 -0.184156 +VERTEX3 781 73.087 -9.76997 42.554 -0.0414415 0.0116755 -0.20629 +VERTEX3 782 73.5787 -7.49873 42.4838 -0.0315206 0.00333684 -0.206435 +VERTEX3 783 74.438 -5.01415 41.8262 -0.0381511 -0.0177585 -0.2008 +VERTEX3 784 75.1426 -4.79576 41.3239 -0.0198418 -0.00959162 -0.23284 +VERTEX3 785 77.9581 -6.61293 41.1742 0.00238311 -0.0228563 -0.265142 +VERTEX3 786 78.7431 -5.58161 40.6963 0.00792276 0.00433743 -0.255938 +VERTEX3 787 80.315 -9.36942 41.1854 0.053059 -0.0228838 -0.287114 +VERTEX3 788 81.5692 -7.34563 40.9808 0.0554175 0.0384372 -0.265752 +VERTEX3 789 83.744 -9.59211 41.7562 0.0347555 0.0277383 -0.302815 +VERTEX3 790 84.5246 -12.3419 41.6279 -0.0230054 0.0684783 -0.343828 +VERTEX3 791 87.8868 -8.74928 41.5534 0.00324076 0.0175355 -0.314053 +VERTEX3 792 88.8645 -7.3465 41.3252 2.57702e-05 -0.00673755 -0.307821 +VERTEX3 793 91.2667 -5.78782 41.1368 -0.00782841 -0.0273139 -0.286757 +VERTEX3 794 92.8183 -3.20153 40.7896 0.00471264 -0.0363312 -0.238503 +VERTEX3 795 94.4407 0.0806823 40.5364 0.00717885 -0.0433231 -0.209045 +VERTEX3 796 95.0656 3.26784 40.2193 0.00551944 -0.0397135 -0.155485 +VERTEX3 797 95.9004 6.54999 39.9343 -0.00675385 -0.0450258 -0.119225 +VERTEX3 798 96.3202 10.5706 39.5202 -0.0226616 -0.0433004 -0.0374635 +VERTEX3 799 96.025 14.9195 39.1987 -0.0236025 -0.0457592 0.0375302 +VERTEX3 800 95.0195 19.2736 38.8348 -0.0119422 -0.0404395 0.132083 +VERTEX3 801 93.857 24.3492 38.8971 -0.0226028 -0.0403526 0.14339 +VERTEX3 802 92.7406 29.3867 38.8258 -0.0169669 -0.0187487 0.168118 +VERTEX3 803 91.2799 33.1738 38.8249 -0.0226129 -0.00814665 0.189813 +VERTEX3 804 89.7379 37.031 38.9446 -0.0186513 -0.000107412 0.194662 +VERTEX3 805 89.0682 40.563 38.8515 -0.0139417 0.00644184 0.223932 +VERTEX3 806 87.7829 41.2988 39.2151 -0.00478567 -0.011273 0.219388 +VERTEX3 807 86.964 42.3753 38.9821 -0.00454707 -0.0110082 0.218739 +VERTEX3 808 85.6957 40.5741 38.6944 0.00305122 -0.0284001 0.237967 +VERTEX3 809 84.882 42.7515 38.2719 -0.0231545 -0.00731446 0.236306 +VERTEX3 810 83.8131 40.4231 38.4781 -3.83705e-05 -0.0152826 0.244418 +VERTEX3 811 82.8524 36.9522 38.1225 -0.00369005 -0.00789432 0.227375 +VERTEX3 812 82.5977 28.0957 38.4081 -0.0150085 -0.0109505 0.207274 +VERTEX3 813 81.0882 36.1604 38.1444 -0.0087173 0.00569088 0.254475 +VERTEX3 814 80.9047 24.3946 38.0879 0.00845652 0.0168275 0.221295 +VERTEX3 815 80.5387 17.3938 37.9923 -0.0021335 0.00167887 0.238877 +VERTEX3 816 80.307 4.02098 37.699 -0.0179766 0.00718499 0.187857 +VERTEX3 817 79.012 -0.898475 37.3289 -0.0427737 0.0341572 0.17152 +VERTEX3 818 77.2642 2.86946 37.4378 -0.0622276 0.0485225 0.229242 +VERTEX3 819 75.7646 2.58782 37.207 -0.0438448 0.0564378 0.216746 +VERTEX3 820 74.8482 1.24031 37.6436 -0.0231073 0.030577 0.203643 +VERTEX3 821 73.9004 4.07489 37.6685 -0.0279664 0.0371406 0.195663 +VERTEX3 822 73.6673 2.94936 38.1475 -0.0255558 0.0293448 0.159458 +VERTEX3 823 72.679 8.85885 37.8855 -0.0108823 0.0241046 0.180747 +VERTEX3 824 71.6974 13.0255 38.1447 -0.0102513 0.0375358 0.201243 +VERTEX3 825 70.724 20.0533 37.9656 -0.00743145 0.0162494 0.236708 +VERTEX3 826 67.2919 -30.0744 39.0366 -0.0320212 0.0170405 -0.274086 +VERTEX3 827 68.5783 -23.4809 38.7724 -0.0573399 0.0126836 -0.257328 +VERTEX3 828 70.2826 -18.7485 38.2906 -0.0589858 0.0120071 -0.224974 +VERTEX3 829 71.9206 -10.4943 37.6911 -0.0392262 0.0192259 -0.187423 +VERTEX3 830 73.2034 -11.2044 37.2975 -0.0430428 0.00797433 -0.208217 +VERTEX3 831 73.0549 -9.13192 36.924 -0.033209 0.000154555 -0.212667 +VERTEX3 832 74.3147 -7.18577 36.5472 -0.0406435 -0.0171191 -0.20553 +VERTEX3 833 75.0206 -8.45688 35.999 -0.0345958 -0.0118897 -0.25543 +VERTEX3 834 77.8891 -8.4156 35.7036 -0.00698505 -0.0205155 -0.255737 +VERTEX3 835 78.4648 -7.86034 35.0958 0.0141115 0.00500525 -0.264488 +VERTEX3 836 80.2538 -10.2391 35.5922 0.0438854 -0.0265048 -0.271478 +VERTEX3 837 81.5518 -12.4397 35.45 0.0649043 0.0387323 -0.260491 +VERTEX3 838 83.5886 -13.5825 36.2531 0.0424768 0.0208539 -0.314221 +VERTEX3 839 84.2149 -13.7229 36.1698 -0.0104683 0.0668428 -0.356279 +VERTEX3 840 87.3919 -10.4633 36.1704 0.011558 0.0189238 -0.327891 +VERTEX3 841 88.74 -10.3418 36.027 -0.0106985 -0.0110454 -0.335305 +VERTEX3 842 91.2524 -8.65395 35.71 -0.00443315 -0.0310386 -0.328439 +VERTEX3 843 93.1161 -6.09449 35.3348 0.0171112 -0.0410631 -0.282354 +VERTEX3 844 95.2828 -4.11703 35.0521 0.0198627 -0.0565447 -0.264384 +VERTEX3 845 96.4038 -2.28665 34.7546 0.0266996 -0.0452288 -0.227543 +VERTEX3 846 97.7109 2.35334 34.5295 0.00694717 -0.0522237 -0.177855 +VERTEX3 847 98.5858 6.05717 34.2551 -0.00421416 -0.0512593 -0.117913 +VERTEX3 848 99.1546 11.1278 33.7757 -0.0101386 -0.0519381 -0.0308685 +VERTEX3 849 98.7567 15.6346 33.4199 0.00056047 -0.0462044 0.0525942 +VERTEX3 850 97.5708 20.0513 33.2324 0.0266315 -0.0622728 0.135617 +VERTEX3 851 96.2663 25.1484 33.2657 0.000697124 -0.0504064 0.166284 +VERTEX3 852 94.8456 30.318 33.3895 -0.0125521 -0.0384403 0.177163 +VERTEX3 853 93.5268 35.736 33.2057 -0.00995911 -0.0172135 0.198969 +VERTEX3 854 91.8318 38.3622 33.1434 -0.0125323 -0.00762999 0.214953 +VERTEX3 855 90.3415 44.3052 33.305 -0.0127198 0.0033146 0.220629 +VERTEX3 856 89.2695 45.8417 33.1504 -0.011064 0.00624199 0.246328 +VERTEX3 857 88.2946 45.8859 33.5598 -0.00159321 -0.0140026 0.237243 +VERTEX3 858 87.4654 46.3885 33.2368 -0.0031829 -0.015908 0.239141 +VERTEX3 859 86.4158 47.2277 33.214 0.000173278 -0.0295058 0.253125 +VERTEX3 860 85.8064 44.0963 32.6225 -0.0249718 -0.0177527 0.236266 +VERTEX3 861 84.5784 43.6517 32.8593 -0.00145867 -0.017607 0.263424 +VERTEX3 862 83.6176 41.3757 32.4042 -0.00564905 -0.0114591 0.252432 +VERTEX3 863 83.7441 37.4903 32.5499 -0.00575323 -0.017266 0.237605 +VERTEX3 864 82.4906 34.3058 32.2993 0.00167366 -0.00974163 0.257162 +VERTEX3 865 82.0892 25.4482 32.3694 0.00605039 0.0133082 0.237301 +VERTEX3 866 81.5089 17.9967 32.2501 -0.00400783 0.000332292 0.238348 +VERTEX3 867 81.0099 4.59099 31.9663 -0.0152583 0.0128673 0.212431 +VERTEX3 868 79.5326 -1.14842 31.586 -0.0437149 0.0341829 0.183512 +VERTEX3 869 77.8028 2.54774 31.7857 -0.059978 0.0594901 0.247463 +VERTEX3 870 75.6536 4.04561 31.3373 -0.0560108 0.0624992 0.238044 +VERTEX3 871 75.1147 2.76931 31.9989 -0.0205686 0.0352053 0.212954 +VERTEX3 872 74.7506 3.09072 32.0943 -0.0214248 0.0333909 0.170928 +VERTEX3 873 74.0016 4.5285 32.4901 -0.0194581 0.0338776 0.161565 +VERTEX3 874 73.139 12.2032 32.3358 -0.0094863 0.0395323 0.207347 +VERTEX3 875 73.1067 13.8325 32.6051 -0.0130038 0.022361 0.183678 +VERTEX3 876 69.7281 -24.8338 33.1706 -0.0307646 0.0188661 -0.207228 +VERTEX3 877 70.4405 -21.4706 32.8854 -0.0437953 0.0168858 -0.207635 +VERTEX3 878 71.3222 -16.2964 32.5547 -0.0597641 0.0193163 -0.202945 +VERTEX3 879 73.2791 -12.3453 32.0608 -0.0518969 0.0203363 -0.190549 +VERTEX3 880 73.2382 -11.331 31.6985 -0.0493152 0.000119803 -0.222079 +VERTEX3 881 73.749 -11.9299 31.2457 -0.0571868 0.00124496 -0.236902 +VERTEX3 882 74.653 -10.1745 30.5677 -0.0329956 -0.00853775 -0.233008 +VERTEX3 883 77.6594 -10.1384 30.2416 -0.0175852 -0.0165183 -0.250383 +VERTEX3 884 77.7468 -8.27746 29.4923 0.000793561 -0.0127203 -0.254147 +VERTEX3 885 79.715 -11.4812 29.8763 0.0360046 -0.0306003 -0.270512 +VERTEX3 886 81.0369 -13.7286 29.75 0.0697085 0.0277705 -0.263992 +VERTEX3 887 83.0948 -15.7549 30.6753 0.0375469 0.0235328 -0.308433 +VERTEX3 888 83.0023 -13.6896 30.3636 -0.000871611 0.0634918 -0.358004 +VERTEX3 889 86.4098 -12.0574 30.4155 0.0180877 0.0200957 -0.331328 +VERTEX3 890 87.8663 -10.724 30.3759 -0.00333483 -0.00808121 -0.351829 +VERTEX3 891 90.6222 -10.0913 30.0743 -0.00597919 -0.0321591 -0.337831 +VERTEX3 892 92.6995 -7.07631 29.7262 0.0238818 -0.0471227 -0.318546 +VERTEX3 893 95.1121 -7.38781 29.3345 0.0308118 -0.0652476 -0.312641 +VERTEX3 894 96.5973 -6.61514 29.0656 0.0410534 -0.0480305 -0.2923 +VERTEX3 895 98.667 -1.85419 28.9821 0.0244347 -0.0558943 -0.237912 +VERTEX3 896 99.9638 2.7128 28.6754 0.00924538 -0.0536852 -0.176145 +VERTEX3 897 101.226 6.3945 28.3438 0.000173633 -0.0569418 -0.101465 +VERTEX3 898 101.484 11.8024 27.9604 0.00986498 -0.0457209 -0.032121 +VERTEX3 899 101.144 16.1471 27.7207 0.0299245 -0.0563168 0.0593548 +VERTEX3 900 99.6968 20.8425 27.4657 0.0347954 -0.0569954 0.159849 +VERTEX3 901 98.3941 26.5844 27.7623 0.0204176 -0.0585735 0.169055 +VERTEX3 902 96.7939 31.33 27.6178 0.00393892 -0.051798 0.196495 +VERTEX3 903 95.3227 37.4575 27.8083 -0.0122295 -0.0354355 0.203057 +VERTEX3 904 93.6451 41.2732 27.4248 -0.00562051 -0.0148934 0.228244 +VERTEX3 905 92.0787 46.611 27.3374 -0.00684606 -0.00466384 0.248122 +VERTEX3 906 90.2291 49.1868 27.5153 -0.00871402 0.00695026 0.242556 +VERTEX3 907 89.2189 50.748 27.3696 -0.00497306 0.0053735 0.265452 +VERTEX3 908 88.5949 49.5354 27.8253 0.000800117 -0.0152455 0.251022 +VERTEX3 909 87.696 50.514 27.5513 -0.000499234 -0.0200351 0.256319 +VERTEX3 910 86.4485 50.842 27.4135 0.00215842 -0.0326726 0.268397 +VERTEX3 911 86.1179 47.5161 26.6507 -0.024731 -0.0187803 0.242995 +VERTEX3 912 84.1803 49.8089 27.0392 -0.00350032 -0.0206321 0.276078 +VERTEX3 913 83.3772 51.8799 26.4659 -0.00098724 -0.00835962 0.297469 +VERTEX3 914 84.2711 42.5083 26.7628 0.00197912 -0.0198422 0.261959 +VERTEX3 915 83.2214 36.1383 26.4487 -0.00715951 -0.00534549 0.273038 +VERTEX3 916 82.7248 28.2329 26.5524 0.00686666 0.0135867 0.250236 +VERTEX3 917 82.004 19.3581 26.4645 -0.00259301 3.37616e-05 0.25819 +VERTEX3 918 80.7598 5.48385 26.1246 -0.0165318 0.0283876 0.242756 +VERTEX3 919 79.5061 0.161512 25.7498 -0.0474137 0.0421985 0.230616 +VERTEX3 920 77.2335 3.4575 25.8813 -0.0580096 0.064044 0.253739 +VERTEX3 921 75.2369 6.21816 25.6306 -0.0558128 0.0696474 0.267353 +VERTEX3 922 74.729 6.12524 26.1387 -0.0112882 0.0465818 0.228773 +VERTEX3 923 74.7763 5.32272 26.2992 -0.00961688 0.0461016 0.183113 +VERTEX3 924 74.1887 5.84587 26.9443 -0.0120328 0.0474528 0.192645 +VERTEX3 925 73.7923 12.9829 26.8071 -0.0256166 0.0333401 0.214095 +VERTEX3 926 70.5068 -23.9748 27.4458 -0.0220276 0.0293106 -0.195783 +VERTEX3 927 71.0002 -16.9177 27.2483 -0.0486557 0.0191653 -0.177228 +VERTEX3 928 72.6177 -14.4514 26.9469 -0.0720108 0.00257769 -0.185961 +VERTEX3 929 72.6642 -13.1281 26.4097 -0.0706787 -0.000874428 -0.220108 +VERTEX3 930 73.2739 -12.897 25.7393 -0.0616737 0.00843685 -0.235995 +VERTEX3 931 74.3625 -10.6226 25.1135 -0.033418 0.0063125 -0.202982 +VERTEX3 932 77.0276 -11.6057 24.7292 -0.0341137 -0.0109173 -0.236747 +VERTEX3 933 77.4514 -13.0915 24.1891 0.00678828 -0.016098 -0.243817 +VERTEX3 934 79.2688 -12.9411 24.3967 0.0207257 -0.0301501 -0.25051 +VERTEX3 935 80.258 -14.2014 24.044 0.063558 0.0167009 -0.256097 +VERTEX3 936 81.8866 -18.6372 24.9904 0.0298731 0.0183804 -0.303167 +VERTEX3 937 81.5734 -15.7245 24.4312 0.00297667 0.0610712 -0.359949 +VERTEX3 938 85.2083 -14.222 24.8793 0.0203799 0.0210246 -0.327024 +VERTEX3 939 86.6159 -12.3723 24.7918 0.00223586 -0.00978514 -0.361085 +VERTEX3 940 89.3744 -13.0671 24.4751 -0.00222667 -0.0355754 -0.370197 +VERTEX3 941 91.5297 -9.89542 23.8795 0.029068 -0.0573822 -0.353279 +VERTEX3 942 94.2784 -10.7966 23.4896 0.0422989 -0.0729581 -0.358601 +VERTEX3 943 96.2205 -8.45915 23.3116 0.054727 -0.05195 -0.327713 +VERTEX3 944 98.6851 -6.26479 23.1983 0.0417263 -0.0564506 -0.298154 +VERTEX3 945 100.17 -0.707113 23.0248 0.0223145 -0.0535905 -0.228092 +VERTEX3 946 102.051 3.03715 22.8008 0.0109153 -0.0585798 -0.174902 +VERTEX3 947 103.034 7.38286 22.416 0.0158333 -0.0455272 -0.105752 +VERTEX3 948 103.484 12.4445 22.117 0.0324002 -0.0493337 -0.0189377 +VERTEX3 949 102.966 17.0734 21.89 0.0321838 -0.0470088 0.0641089 +VERTEX3 950 101.634 22.1744 21.6695 0.039753 -0.0508548 0.161744 +VERTEX3 951 99.9691 27.7668 21.9305 0.0289194 -0.0580206 0.176651 +VERTEX3 952 98.4302 32.5789 22.0205 0.0112354 -0.0610046 0.190675 +VERTEX3 953 96.8592 38.7446 21.8941 -0.000252529 -0.0501237 0.225524 +VERTEX3 954 95.089 43.5584 22.0336 -0.0124445 -0.0307544 0.225666 +VERTEX3 955 93.2025 48.7941 21.6299 -0.006095 -0.0104039 0.253492 +VERTEX3 956 91.5333 53.8134 21.5649 -0.00273945 0.000125013 0.279198 +VERTEX3 957 89.4803 54.6467 21.6549 -0.00486466 0.0106214 0.266477 +VERTEX3 958 88.8642 57.0889 21.5423 -0.00273128 0.00828965 0.286329 +VERTEX3 959 88.2896 54.3654 22.0496 0.00194709 -0.0167276 0.264563 +VERTEX3 960 87.3276 55.3366 21.741 0.000725331 -0.0220226 0.271184 +VERTEX3 961 86.5775 55.0778 21.6024 0.00362258 -0.0340009 0.281346 +VERTEX3 962 86.2539 52.5494 20.6746 -0.0236411 -0.0170783 0.257171 +VERTEX3 963 84.399 51.4208 21.1235 -0.00102338 -0.0123666 0.300273 +VERTEX3 964 83.1278 55.0209 20.4727 -0.00582745 -0.0154827 0.325112 +VERTEX3 965 84.6683 42.004 20.8796 -0.00994202 -0.0276856 0.266623 +VERTEX3 966 83.5542 39.0583 20.679 -0.00286224 -0.00905735 0.292355 +VERTEX3 967 82.9071 30.7273 20.6806 0.00493734 0.00650257 0.270891 +VERTEX3 968 81.8305 19.3204 20.5695 -0.00277313 -0.00169787 0.268242 +VERTEX3 969 80.3722 4.7429 20.1538 -0.0119651 0.0310861 0.265732 +VERTEX3 970 78.6845 1.92812 19.7029 -0.0497548 0.0486225 0.277158 +VERTEX3 971 77.2026 2.05097 20.3088 -0.0445525 0.0541222 0.261656 +VERTEX3 972 74.9811 6.41803 20.0193 -0.0186081 0.0489899 0.262336 +VERTEX3 973 74.3459 6.75042 20.4866 -0.00436457 0.0625445 0.247019 +VERTEX3 974 74.7373 4.54161 20.8993 -0.000237355 0.0625423 0.217772 +VERTEX3 975 74.2481 6.98282 21.4618 -0.0114457 0.043441 0.231035 +VERTEX3 976 71.3154 -17.9418 21.5599 -0.0134231 0.0637925 -0.0799272 +VERTEX3 977 72.4889 -15.2809 21.4502 -0.084949 -0.0167412 -0.231205 +VERTEX3 978 71.8983 -16.0828 21.2591 -0.0722491 -0.0197962 -0.197553 +VERTEX3 979 72.3665 -16.5163 20.5118 -0.0592749 0.0223235 -0.236633 +VERTEX3 980 73.4875 -10.7543 19.5943 -0.0420552 0.0163662 -0.18926 +VERTEX3 981 75.7206 -13.2541 19.2045 -0.0507122 0.000988665 -0.224742 +VERTEX3 982 76.605 -13.6306 18.5088 0.000383505 -0.0251016 -0.223081 +VERTEX3 983 77.8688 -15.8177 18.6647 0.00806814 -0.0306323 -0.232068 +VERTEX3 984 79.3684 -15.9341 18.2883 0.0581428 -0.00737198 -0.245057 +VERTEX3 985 81.0947 -22.0888 19.3175 0.0254135 0.0081612 -0.298464 +VERTEX3 986 80.0695 -19.5136 18.748 0.0165622 0.0598972 -0.348013 +VERTEX3 987 83.4792 -18.3581 18.9665 0.0208834 0.0231857 -0.324326 +VERTEX3 988 84.7701 -15.0997 18.9671 0.00312498 -0.0136693 -0.363368 +VERTEX3 989 87.5586 -16.7254 18.6985 -0.00305111 -0.0361276 -0.378381 +VERTEX3 990 89.909 -13.6044 18.0683 0.0310584 -0.0622628 -0.38263 +VERTEX3 991 92.7955 -12.9515 17.6429 0.0443947 -0.0800941 -0.386392 +VERTEX3 992 94.6637 -11.9511 17.3596 0.0639286 -0.0553061 -0.373527 +VERTEX3 993 97.5529 -9.58343 17.2539 0.0544127 -0.0550978 -0.346805 +VERTEX3 994 99.3036 -5.16331 17.1218 0.0355688 -0.0523035 -0.30214 +VERTEX3 995 101.934 -0.992612 17.0735 0.0166943 -0.0547902 -0.228097 +VERTEX3 996 103.385 3.71844 16.8065 0.0193303 -0.0424914 -0.173705 +VERTEX3 997 104.588 8.78346 16.363 0.03407 -0.0440226 -0.0908203 +VERTEX3 998 104.842 13.019 16.157 0.0287244 -0.0372216 -0.0220955 +VERTEX3 999 104.312 18.0013 15.9781 0.0351795 -0.0322261 0.0506716 +VERTEX3 1000 103.059 23.5471 15.7369 0.0567426 -0.0347185 0.142488 +VERTEX3 1001 101.478 29.4407 16.0243 0.0362124 -0.0550921 0.173532 +VERTEX3 1002 99.6448 34.2147 16.1992 0.0211697 -0.0580943 0.196127 +VERTEX3 1003 98.033 39.0053 16.0925 0.00387875 -0.0572551 0.213185 +VERTEX3 1004 96.2053 45.5429 15.9275 -0.00531061 -0.0460444 0.245362 +VERTEX3 1005 94.3354 49.5051 16.137 -0.0139756 -0.0260709 0.247183 +VERTEX3 1006 92.2028 54.8705 15.6485 -0.00589873 -0.00394912 0.276759 +VERTEX3 1007 90.5383 57.7502 15.5878 0.00153185 0.00349447 0.294959 +VERTEX3 1008 88.446 60.2033 15.6233 -0.00327507 0.0143891 0.287386 +VERTEX3 1009 87.9058 62.2535 15.6966 0.000199508 0.011241 0.300907 +VERTEX3 1010 87.5657 61.9897 16.267 0.00327557 -0.0134803 0.282594 +VERTEX3 1011 87.2116 60.8158 15.9751 0.00302768 -0.0227211 0.281374 +VERTEX3 1012 85.8404 59.7814 15.6865 0.00512056 -0.0338918 0.294016 +VERTEX3 1013 85.9062 56.5297 14.5287 -0.0264257 -0.0179655 0.267583 +VERTEX3 1014 83.489 58.8127 15.1612 -0.00549742 -0.0229229 0.313435 +VERTEX3 1015 82.3266 60.3477 14.4305 -0.00508877 -0.0253363 0.340382 +VERTEX3 1016 84.83 44.8781 15.153 -0.0068276 -0.0289127 0.280193 +VERTEX3 1017 83.1924 43.9899 14.8601 -0.0177938 -0.0239789 0.308191 +VERTEX3 1018 82.2075 29.5092 14.8343 0.00792855 0.00633603 0.270182 +VERTEX3 1019 80.7783 19.4151 14.6167 -0.00438154 -0.00178099 0.286908 +VERTEX3 1020 79.6416 5.31413 14.2246 -0.0103099 0.0314893 0.280166 +VERTEX3 1021 78.0447 1.75878 14.1411 -0.0511027 0.0525858 0.313705 +VERTEX3 1022 76.6016 2.73504 14.6745 -0.0307107 0.045673 0.283702 +VERTEX3 1023 74.2846 7.07883 14.3983 0.0417928 0.0366766 0.308824 +VERTEX3 1024 74.6987 3.82253 15.2711 -0.0125278 0.0603764 0.253178 +VERTEX3 1025 74.56 5.55644 15.5142 -0.0222571 0.0430691 0.262186 +VERTEX3 1026 72.0891 -16.3254 15.6669 0.0272022 0.103421 0.204902 +VERTEX3 1027 70.8741 -16.9322 16.4689 -0.154163 0.0665954 -0.131188 +VERTEX3 1028 71.1441 -17.7772 15.1644 -0.0623474 0.0269729 -0.197359 +VERTEX3 1029 72.2123 -16.9733 14.5827 -0.0835868 0.030437 -0.203723 +VERTEX3 1030 74.2312 -16.9886 13.7905 -0.065445 0.0213744 -0.233468 +VERTEX3 1031 75.777 -14.4302 13.1075 -0.033349 -0.0461558 -0.161794 +VERTEX3 1032 76.6549 -16.9379 13.0264 -0.00292766 -0.0266126 -0.209676 +VERTEX3 1033 78.0858 -19.2748 12.7828 0.0471608 -0.018565 -0.222569 +VERTEX3 1034 78.9553 -24.7999 13.6334 0.0143672 -0.00147636 -0.288723 +VERTEX3 1035 77.9972 -21.969 12.9853 0.00345983 0.0605983 -0.352317 +VERTEX3 1036 81.8997 -18.3567 13.1205 0.014137 0.0173411 -0.301855 +VERTEX3 1037 82.7793 -18.1004 13.0889 -0.00268413 -0.0229934 -0.365076 +VERTEX3 1038 85.4287 -18.4498 12.8427 -0.00325741 -0.0366004 -0.380648 +VERTEX3 1039 87.5612 -17.857 12.0295 0.032071 -0.0646141 -0.402586 +VERTEX3 1040 90.576 -16.3985 11.568 0.0515019 -0.083921 -0.416585 +VERTEX3 1041 92.4336 -15.182 11.4057 0.071597 -0.0575257 -0.40918 +VERTEX3 1042 95.5028 -11.6297 11.3424 0.05789 -0.0509776 -0.376418 +VERTEX3 1043 97.7294 -7.96817 11.2854 0.0410403 -0.0493845 -0.335244 +VERTEX3 1044 100.657 -5.58522 11.1742 0.0283111 -0.0516512 -0.304338 +VERTEX3 1045 102.686 0.195165 11.0102 0.0243595 -0.0385792 -0.222763 +VERTEX3 1046 104.604 3.92122 10.6118 0.0334331 -0.0370405 -0.173662 +VERTEX3 1047 105.453 8.3456 10.3802 0.0268666 -0.0259976 -0.110039 +VERTEX3 1048 105.663 13.265 10.152 0.033592 -0.0257298 -0.0378955 +VERTEX3 1049 105.281 18.6176 10.0071 0.0547692 -0.0161271 0.033409 +VERTEX3 1050 104.049 25.1756 9.83788 0.0524174 -0.0298727 0.117444 +VERTEX3 1051 102.433 30.7741 10.1642 0.0469431 -0.0414216 0.152721 +VERTEX3 1052 100.783 36.3091 10.2324 0.029336 -0.0583167 0.185222 +VERTEX3 1053 98.7084 41.2081 10.3377 0.0108505 -0.0612033 0.20879 +VERTEX3 1054 97.1854 46.8218 10.1862 -0.00209071 -0.0494368 0.239328 +VERTEX3 1055 94.9752 51.6894 9.88676 -0.0110411 -0.0403209 0.263726 +VERTEX3 1056 93.052 56.1167 10.1402 -0.0133659 -0.0190963 0.271172 +VERTEX3 1057 90.8342 59.7553 9.58889 -0.00735591 0.00678266 0.293863 +VERTEX3 1058 89.0091 63.083 9.56128 0.00330238 0.00618845 0.310975 +VERTEX3 1059 87.0242 67.8012 9.80051 -0.0016365 0.0202865 0.304731 +VERTEX3 1060 86.5918 67.3307 9.72973 0.00461268 0.0123604 0.311799 +VERTEX3 1061 86.1976 67.4326 10.4486 0.00288173 -0.0122339 0.298519 +VERTEX3 1062 86.0268 64.5473 9.9268 0.00700723 -0.0206937 0.291 +VERTEX3 1063 85.3206 63.8789 9.76569 0.00600014 -0.0349044 0.309439 +VERTEX3 1064 85.1126 58.1053 8.56229 -0.0279744 -0.0185489 0.275693 +VERTEX3 1065 83.1152 61.2275 9.29973 -0.00611334 -0.0219216 0.339296 +VERTEX3 1066 82.4299 60.9155 8.54346 -0.00798345 -0.0145973 0.340313 +VERTEX3 1067 84.1484 48.5787 9.09265 -0.00414128 -0.0286877 0.297156 +VERTEX3 1068 82.469 43.3929 8.92641 -0.0103722 -0.0307413 0.323927 +VERTEX3 1069 80.6045 29.4122 8.82315 0.00495913 0.00138174 0.274921 +VERTEX3 1070 79.5957 26.1971 8.815 -0.00771985 0.00143876 0.323087 +VERTEX3 1071 78.4377 6.60274 8.54425 -0.0116461 0.0278558 0.294852 +VERTEX3 1072 77.0218 1.83283 8.45629 -0.052328 0.0523211 0.323391 +VERTEX3 1073 75.7967 3.73625 9.16428 -0.0397738 0.0295847 0.282703 +VERTEX3 1074 73.733 7.00582 8.95756 -0.0426107 0.0816772 0.41614 +VERTEX3 1075 74.297 3.0349 9.59858 -0.0118396 0.0498902 0.380706 +VERTEX3 1076 70.9067 -14.1333 9.97449 0.0527306 0.0913325 0.248182 +VERTEX3 1077 69.0805 -17.4387 9.78211 -0.0504505 0.0247129 -0.103869 +VERTEX3 1078 69.6357 -16.2457 8.99165 -0.0745709 0.0402424 -0.163997 +VERTEX3 1079 73.0864 -14.2112 8.25149 -0.0474728 0.0427071 -0.170023 +VERTEX3 1080 74.0658 -12.5749 7.58748 -0.0595483 -0.0277258 -0.105523 +VERTEX3 1081 75.4478 -15.9866 7.35953 -0.0297052 -0.0120624 -0.172575 +VERTEX3 1082 76.7504 -19.3263 7.06845 0.0229341 -0.0332858 -0.200387 +VERTEX3 1083 77.9899 -24.6449 7.84722 0.00251242 -0.0101493 -0.264447 +VERTEX3 1084 75.9264 -23.7363 7.19821 -0.00025484 0.0556789 -0.343579 +VERTEX3 1085 79.925 -20.4486 7.16773 0.0176384 0.0109517 -0.289693 +VERTEX3 1086 80.5511 -19.5898 7.08443 -0.00963365 -0.0201353 -0.358975 +VERTEX3 1087 82.8584 -21.2152 6.94671 -0.00401899 -0.0330954 -0.389398 +VERTEX3 1088 85.04 -18.6722 6.0578 0.0307829 -0.0654615 -0.400692 +VERTEX3 1089 88.1031 -19.2311 5.57463 0.0540056 -0.0871013 -0.435743 +VERTEX3 1090 90.031 -16.6817 5.37282 0.0753514 -0.0588239 -0.430361 +VERTEX3 1091 93.0947 -14.4129 5.35833 0.0619494 -0.0480571 -0.405873 +VERTEX3 1092 95.5905 -10.8537 5.41744 0.0476138 -0.0453734 -0.375658 +VERTEX3 1093 98.7482 -8.94825 5.2924 0.0310372 -0.0480703 -0.341183 +VERTEX3 1094 101.064 -3.92651 5.18875 0.0250489 -0.0328766 -0.280168 +VERTEX3 1095 103.394 -0.216954 4.79049 0.0313675 -0.0296326 -0.249139 +VERTEX3 1096 104.772 3.48071 4.44237 0.0263016 -0.0163983 -0.18878 +VERTEX3 1097 105.758 8.53782 4.22271 0.0335165 -0.0185501 -0.119101 +VERTEX3 1098 106.029 13.2948 4.09344 0.0515731 -0.00311782 -0.0543766 +VERTEX3 1099 105.556 20.0903 4.0138 0.060231 -0.00562593 0.0208155 +VERTEX3 1100 104.581 26.8045 3.8212 0.0534378 0.00738774 0.0788925 +VERTEX3 1101 103.061 32.6529 4.18499 0.0352346 -0.0286862 0.124853 +VERTEX3 1102 101.343 38.017 4.40792 0.0342876 -0.0455287 0.166797 +VERTEX3 1103 99.4872 43.178 4.41695 0.0205583 -0.0592937 0.200461 +VERTEX3 1104 97.4773 48.9336 4.45999 0.0035384 -0.0514108 0.231046 +VERTEX3 1105 95.7011 52.4884 4.10206 -0.0139579 -0.050723 0.249699 +VERTEX3 1106 93.3739 58.63 3.76858 -0.0151554 -0.0347248 0.288613 +VERTEX3 1107 91.166 62.1013 3.96115 -0.0134389 -0.0127829 0.295347 +VERTEX3 1108 89.1375 65.1188 3.53013 -0.00710201 0.014834 0.31449 +VERTEX3 1109 87.0454 68.7599 3.64186 0.00635931 0.0110297 0.326754 +VERTEX3 1110 85.3282 71.4602 3.74147 0.00504343 0.0207078 0.324972 +VERTEX3 1111 84.8627 72.5008 3.76079 0.00561304 0.0140077 0.324679 +VERTEX3 1112 84.5908 71.1852 4.48655 0.00442932 -0.012333 0.310984 +VERTEX3 1113 84.059 69.2736 4.03383 0.00875011 -0.0186635 0.302126 +VERTEX3 1114 83.8852 66.842 3.80061 0.00478991 -0.0359672 0.316757 +VERTEX3 1115 84.5278 61.7495 2.52458 -0.0308112 -0.0147507 0.288066 +VERTEX3 1116 82.4167 63.2503 3.55227 -0.00851416 -0.0324323 0.348165 +VERTEX3 1117 82.1822 60.3009 2.79166 -0.00855047 -0.0224177 0.345507 +VERTEX3 1118 84.0394 46.4225 3.35743 -0.00731408 -0.0300463 0.299373 +VERTEX3 1119 81.6301 36.1146 3.05559 -0.0120528 -0.00461644 0.318332 +VERTEX3 1120 79.6203 27.9383 3.24562 0.0172242 0.00450319 0.265146 +VERTEX3 1121 78.3271 22.9335 3.24499 -0.0092568 -0.00474733 0.305913 +VERTEX3 1122 78.1991 5.30328 3.17077 -0.011837 0.00675399 0.25816 +VERTEX3 1123 76.3549 -0.405883 3.05963 -0.0571119 0.0504622 0.336787 +VERTEX3 1124 75.1435 3.27147 3.66389 -0.043601 0.0304841 0.436928 +VERTEX3 1125 73.9272 3.68146 3.54846 -0.0259989 0.0405054 0.454005 +VERTEX3 1126 71.0879 -10.9191 3.99045 -0.0016906 0.0275773 0.28656 +VERTEX3 1127 68.6473 -12.6955 3.58655 0.0099481 0.0416466 -0.0335375 +VERTEX3 1128 71.9007 -13.5569 3.05133 -0.0283895 0.0554242 -0.104567 +VERTEX3 1129 71.9901 -13.6566 2.71191 -0.108653 0.0218727 -0.0324667 +VERTEX3 1130 74.031 -15.9882 1.91786 -0.0422108 -0.0134503 -0.149036 +VERTEX3 1131 74.9646 -17.9905 1.37685 0.00526312 -0.0207965 -0.159201 +VERTEX3 1132 76.0395 -23.4177 2.02514 -0.0134217 -0.018847 -0.236866 +VERTEX3 1133 74.7787 -22.1051 1.22647 0.00604903 0.039518 -0.319973 +VERTEX3 1134 77.4737 -24.0712 1.30703 0.035623 0.0111688 -0.292155 +VERTEX3 1135 78.0862 -22.4798 1.0933 -0.0194445 -0.0321828 -0.348415 +VERTEX3 1136 80.2091 -24.9782 1.10302 -0.00483399 -0.0334551 -0.38956 +VERTEX3 1137 82.2607 -20.646 0.23251 0.0312612 -0.0682335 -0.402618 +VERTEX3 1138 84.9077 -20.8653 -0.537811 0.056931 -0.0855173 -0.45037 +VERTEX3 1139 87.1853 -18.5195 -0.728383 0.0769378 -0.0582693 -0.441679 +VERTEX3 1140 90.1044 -15.4329 -0.638816 0.0613566 -0.0463688 -0.419436 +VERTEX3 1141 92.5887 -13.8735 -0.621585 0.0528772 -0.0417371 -0.425673 +VERTEX3 1142 96.2038 -12.6049 -0.584942 0.035596 -0.0427828 -0.381603 +VERTEX3 1143 98.4432 -8.99375 -0.68372 0.0200583 -0.0316375 -0.347512 +VERTEX3 1144 101.126 -6.34696 -1.02383 0.0275621 -0.0204383 -0.322799 +VERTEX3 1145 103.201 -0.923875 -1.36371 0.022547 -0.00815101 -0.253114 +VERTEX3 1146 104.595 3.68673 -1.63136 0.0274021 -0.00522803 -0.2048 +VERTEX3 1147 105.573 8.76577 -1.84308 0.0481215 0.00494724 -0.123455 +VERTEX3 1148 105.639 15.2591 -1.88183 0.0563773 0.00680422 -0.0623659 +VERTEX3 1149 105.195 21.5064 -2.00729 0.054831 0.0119975 0.0015033 +VERTEX3 1150 104.508 28.1927 -2.12129 0.0049771 0.029859 0.0484415 +VERTEX3 1151 103.092 33.8413 -1.799 0.0283991 0.00509983 0.104623 +VERTEX3 1152 101.398 39.1976 -1.68573 0.0251964 -0.0298118 0.141874 +VERTEX3 1153 99.6027 44.1795 -1.53527 0.0182617 -0.0485243 0.184597 +VERTEX3 1154 97.6904 49.6092 -1.60859 0.0121987 -0.0561152 0.216082 +VERTEX3 1155 95.5441 54.5546 -1.64772 -0.00536375 -0.0494701 0.248361 +VERTEX3 1156 94.025 60.5839 -2.10452 -0.0192926 -0.0413509 0.272868 +VERTEX3 1157 91.4493 64.739 -2.2575 -0.0213773 -0.0256094 0.310542 +VERTEX3 1158 89.0697 67.7992 -2.14752 -0.013674 -0.00646633 0.314417 +VERTEX3 1159 86.899 72.2487 -2.50285 -0.00422663 0.0198423 0.339628 +VERTEX3 1160 84.7941 74.1652 -2.35951 0.0113365 0.0145124 0.348647 +VERTEX3 1161 83.0857 76.5472 -2.12889 0.00386896 0.0264215 0.335954 +VERTEX3 1162 82.989 76.5902 -2.22657 0.00520651 0.0165107 0.33695 +VERTEX3 1163 82.7849 74.6372 -1.44042 0.00839239 -0.0102914 0.317774 +VERTEX3 1164 82.7661 71.4096 -1.82946 0.00923791 -0.0149831 0.314195 +VERTEX3 1165 82.7714 69.9164 -1.98034 0.00719829 -0.0350717 0.32419 +VERTEX3 1166 83.7627 64.4632 -3.25862 -0.0314086 -0.0129482 0.289852 +VERTEX3 1167 81.6488 64.0252 -2.2093 -0.00752771 -0.0355216 0.360283 +VERTEX3 1168 81.3882 59.5914 -2.9805 -0.0101715 -0.0197099 0.341856 +VERTEX3 1169 82.8554 44.8109 -2.39364 -0.0123337 -0.0297559 0.300386 +VERTEX3 1170 80.8064 38.4605 -2.66169 -0.00519611 -0.0178147 0.317418 +VERTEX3 1171 78.7458 26.5639 -2.41208 0.024552 0.00968293 0.255371 +VERTEX3 1172 77.4778 23.0638 -2.2884 -0.011729 -0.000211783 0.264963 +VERTEX3 1173 77.7003 2.42224 -2.48002 -0.00923401 -0.0300511 0.19307 +VERTEX3 1174 74.9559 -5.65046 -1.9815 -0.0304413 0.00785309 0.109905 +VERTEX3 1175 74.8007 -4.6826 -1.94116 -0.01422 0.0223402 0.24615 +VERTEX3 1176 71.19 -6.58172 -1.79388 0.0254262 0.0383313 0.343171 +VERTEX3 1177 71.2102 -8.99473 -2.24042 0.0494784 0.0556124 0.108021 +VERTEX3 1178 69.9164 -11.9516 -2.28158 -0.244774 0.183036 0.0554382 +VERTEX3 1179 72.3187 -14.8375 -3.46759 -0.0528585 0.000143584 -0.0951997 +VERTEX3 1180 72.3564 -14.3747 -4.2234 -0.0318443 -0.0158956 -0.12011 +VERTEX3 1181 73.6601 -21.7836 -3.83033 -0.0284435 -0.0351781 -0.20329 +VERTEX3 1182 72.367 -21.6338 -4.58437 0.0102437 0.0215603 -0.296056 +VERTEX3 1183 75.3178 -21.8377 -4.4979 0.0363644 0.000101474 -0.255328 +VERTEX3 1184 75.8572 -23.7876 -4.66691 -0.0129793 -0.031842 -0.328701 +VERTEX3 1185 77.3953 -24.3165 -4.70552 -0.00278642 -0.0288893 -0.354624 +VERTEX3 1186 79.0313 -21.206 -5.55861 0.0345001 -0.0835213 -0.397493 +VERTEX3 1187 81.8557 -23.0224 -6.45638 0.0569626 -0.0848289 -0.442944 +VERTEX3 1188 83.8299 -19.7487 -6.5691 0.0767704 -0.0590772 -0.444839 +VERTEX3 1189 86.7369 -19.682 -6.66512 0.0676505 -0.0536447 -0.457568 +VERTEX3 1190 88.7403 -19.022 -6.48968 0.0560508 -0.0387112 -0.483934 +VERTEX3 1191 92.6238 -14.4447 -6.45597 0.0382809 -0.0384081 -0.410918 +VERTEX3 1192 95.4547 -13.3407 -6.347 0.0172319 -0.0271912 -0.39596 +VERTEX3 1193 98.3728 -7.81299 -6.83 0.0254097 -0.0117048 -0.348058 +VERTEX3 1194 100.653 -4.04911 -7.18494 0.0205976 -0.00231736 -0.309434 +VERTEX3 1195 102.522 -0.111635 -7.40569 0.0270601 0.000834624 -0.262415 +VERTEX3 1196 104.081 4.91688 -7.65039 0.0444182 0.013127 -0.189849 +VERTEX3 1197 104.559 9.9534 -7.70826 0.0568354 0.0180718 -0.141309 +VERTEX3 1198 104.616 16.2397 -7.87332 0.0574717 0.0143763 -0.0728839 +VERTEX3 1199 104.4 22.3491 -7.77876 0.0121502 0.0194916 -0.0158936 +VERTEX3 1200 103.843 29.1796 -8.08152 -0.0222252 0.0443297 0.0251871 +VERTEX3 1201 102.725 35.1721 -7.87865 0.0111388 0.0154574 0.0793328 +VERTEX3 1202 101.052 40.4 -7.63602 0.015829 -0.00256088 0.132833 +VERTEX3 1203 99.4174 46.1929 -7.51763 0.0144497 -0.0302346 0.168078 +VERTEX3 1204 97.4595 50.9988 -7.50154 0.00324392 -0.0460781 0.200278 +VERTEX3 1205 95.4946 56.5468 -7.592 0.00129658 -0.0551516 0.235621 +VERTEX3 1206 93.3879 61.7356 -7.77506 -0.0118536 -0.0425861 0.269998 +VERTEX3 1207 91.5268 65.374 -8.25697 -0.0263303 -0.0374612 0.286493 +VERTEX3 1208 88.9754 70.1111 -8.48761 -0.0224097 -0.0200942 0.32525 +VERTEX3 1209 86.435 72.7001 -8.42822 -0.0117433 -0.00129605 0.333494 +VERTEX3 1210 83.9232 79.9047 -8.28781 0.00143508 0.0235472 0.364819 +VERTEX3 1211 82.3857 79.4995 -8.14862 0.0129676 0.017167 0.363883 +VERTEX3 1212 80.7115 81.8337 -8.00759 0.00456137 0.0289059 0.35001 +VERTEX3 1213 81.3761 78.8663 -8.12064 0.0036436 0.0205111 0.347022 +VERTEX3 1214 81.2059 77.3703 -7.26258 0.00858498 -0.00522576 0.324095 +VERTEX3 1215 81.2077 75.675 -7.53534 0.0078726 -0.0173893 0.328179 +VERTEX3 1216 81.8475 72.3103 -7.73306 0.0148957 -0.0380784 0.331014 +VERTEX3 1217 83.3369 61.5672 -8.92893 -0.03144 -0.0168632 0.287905 +VERTEX3 1218 80.3288 65.004 -7.97729 0.00179872 -0.0219542 0.376629 +VERTEX3 1219 80.6719 52.7105 -8.84282 -0.0153042 -0.0128739 0.325965 +VERTEX3 1220 81.1243 43.1771 -8.22468 -0.0175829 -0.0374032 0.303956 +VERTEX3 1221 79.2687 31.1219 -8.37012 -0.00311982 -0.00471273 0.314959 +VERTEX3 1222 77.7435 18.1455 -8.31572 -0.00486642 -0.00103523 0.24348 +VERTEX3 1223 76.4913 3.9214 -8.02426 0.00616318 0.00724347 0.134074 +VERTEX3 1224 76.8507 -7.39855 -8.24748 0.0225994 -0.0675278 0.0804446 +VERTEX3 1225 74.5392 -12.2109 -7.86857 -0.0277796 -0.00889509 0.103939 +VERTEX3 1226 72.8447 -7.79649 -7.77953 0.00467399 0.0094727 0.320118 +VERTEX3 1227 68.4314 -9.79474 -7.85742 0.106297 0.13256 0.245586 +VERTEX3 1228 70.4801 -15.4665 -8.25776 -0.0298713 0.0267168 0.0278861 +VERTEX3 1229 70.304 -16.9267 -8.87985 -0.172882 -0.10602 -0.0553573 +VERTEX3 1230 71.4626 -20.9224 -9.36886 -0.0442628 -0.0391052 -0.153547 +VERTEX3 1231 71.3899 -22.735 -10.3921 0.033463 -0.0246688 -0.232201 +VERTEX3 1232 74.3376 -23.2969 -10.0983 0.0350362 -0.0267105 -0.208303 +VERTEX3 1233 73.9003 -24.9648 -10.6262 0.00436445 -0.0346488 -0.305409 +VERTEX3 1234 74.863 -27.8742 -10.5354 0.000231151 -0.0329434 -0.36957 +VERTEX3 1235 76.269 -21.8104 -11.2598 0.0354941 -0.0726451 -0.390089 +VERTEX3 1236 78.7359 -23.8755 -12.335 0.0541377 -0.0762931 -0.426262 +VERTEX3 1237 80.3579 -20.6291 -12.4358 0.0706984 -0.0636366 -0.431544 +VERTEX3 1238 83.1522 -20.6376 -12.4364 0.063751 -0.0544011 -0.462854 +VERTEX3 1239 84.9823 -21.3294 -12.2842 0.0546657 -0.0359992 -0.51037 +VERTEX3 1240 88.8323 -16.6923 -12.1486 0.0367786 -0.0350916 -0.45254 +VERTEX3 1241 91.8436 -13.932 -12.039 0.00987791 -0.0201408 -0.421532 +VERTEX3 1242 94.6722 -11.6554 -12.5001 0.0177186 -0.00605775 -0.422882 +VERTEX3 1243 97.0659 -9.30018 -12.8274 0.0142468 0.00518579 -0.366077 +VERTEX3 1244 99.3893 -4.22684 -13.2085 0.0204033 0.0112127 -0.324095 +VERTEX3 1245 101.399 0.685483 -13.4528 0.0419652 0.0262226 -0.259598 +VERTEX3 1246 102.394 5.67334 -13.5837 0.0524014 0.020915 -0.210373 +VERTEX3 1247 102.975 10.8643 -13.6766 0.0620211 0.015636 -0.141583 +VERTEX3 1248 103.18 16.7522 -13.4299 0.0253194 0.00519764 -0.0824193 +VERTEX3 1249 103.059 23.3656 -13.5369 -0.0111815 0.0178306 -0.0378081 +VERTEX3 1250 102.808 30.1016 -13.9724 -0.0351439 0.0340978 0.0195871 +VERTEX3 1251 101.737 35.837 -13.9076 -0.00507266 0.0257768 0.0631085 +VERTEX3 1252 100.339 41.7433 -13.6094 0.0109674 0.00499879 0.109786 +VERTEX3 1253 98.6079 47.3103 -13.4714 0.0100093 -0.0096757 0.160022 +VERTEX3 1254 96.7215 52.3238 -13.4062 0.00667019 -0.0318488 0.194675 +VERTEX3 1255 94.8292 57.3973 -13.4875 -0.00900545 -0.0469279 0.223037 +VERTEX3 1256 92.8733 63.1951 -13.6297 -0.00750391 -0.0526985 0.254019 +VERTEX3 1257 90.6304 67.5191 -13.9199 -0.0200651 -0.0340821 0.293177 +VERTEX3 1258 89.26 70.9867 -14.5062 -0.0336553 -0.0346251 0.299157 +VERTEX3 1259 86.2376 74.4509 -14.687 -0.0223353 -0.0133562 0.339903 +VERTEX3 1260 83.7456 77.5298 -14.301 -0.0127067 0.0042866 0.348598 +VERTEX3 1261 80.8097 83.5533 -14.1857 0.00339609 0.0289195 0.381964 +VERTEX3 1262 79.8981 82.9545 -14.163 0.0222862 0.0205641 0.385028 +VERTEX3 1263 77.9405 83.858 -13.9108 0.00856015 0.0331153 0.360828 +VERTEX3 1264 79.0054 80.1391 -13.8371 0.00253496 0.0285421 0.348501 +VERTEX3 1265 79.2694 79.6859 -13.0246 0.00904043 0.00253342 0.332408 +VERTEX3 1266 78.8514 81.3109 -13.246 0.00929292 -0.0156473 0.341458 +VERTEX3 1267 80.4501 75.1182 -13.4117 0.0205318 -0.0299432 0.339813 +VERTEX3 1268 81.5368 66.5022 -14.9471 -0.0306462 -0.00562778 0.293715 +VERTEX3 1269 79.9173 63.396 -13.7231 -0.00327021 -0.0195656 0.360888 +VERTEX3 1270 79.9252 51.1734 -14.5626 -0.0187616 -0.00993927 0.317786 +VERTEX3 1271 80.6412 41.6909 -13.795 -0.0191426 -0.0382995 0.304714 +VERTEX3 1272 79.674 37.0047 -14.0273 -0.0266299 0.0129488 0.315192 +VERTEX3 1273 77.3278 13.6183 -14.2667 -0.0224451 -0.011642 0.216951 +VERTEX3 1274 75.4748 -0.0613323 -14.2328 0.00630963 -0.0114561 0.13767 +VERTEX3 1275 76.6455 -8.44618 -14.1607 0.0317513 -0.0257725 0.174075 +VERTEX3 1276 73.483 -15.7754 -13.7801 -0.0330723 -0.0153088 0.178813 +VERTEX3 1277 71.5966 -17.2679 -13.7028 -0.0108484 0.00864999 0.135935 +VERTEX3 1278 68.9605 -18.0136 -13.9107 0.0242787 0.143726 0.180315 +VERTEX3 1279 71.1862 -22.943 -14.4225 -0.049479 -0.0771943 -0.0841227 +VERTEX3 1280 71.1407 -23.5583 -16.1346 0.144646 -0.179537 0.000220692 +VERTEX3 1281 72.4185 -23.4654 -15.6694 0.0258126 -0.0590649 -0.147387 +VERTEX3 1282 71.5181 -24.3114 -16.5327 0.0459855 -0.0309742 -0.271359 +VERTEX3 1283 72.6632 -27.8453 -16.314 0.0218294 -0.0265078 -0.339001 +VERTEX3 1284 72.8953 -26.6179 -17.3429 0.0417885 -0.0731508 -0.384789 +VERTEX3 1285 75.3258 -22.6736 -17.9111 0.048001 -0.0688159 -0.377722 +VERTEX3 1286 77.0138 -22.1895 -18.1304 0.0737441 -0.0731059 -0.420926 +VERTEX3 1287 78.8563 -21.6363 -18.2697 0.0573669 -0.06393 -0.464765 +VERTEX3 1288 80.2678 -21.059 -18.041 0.0555 -0.0358356 -0.510032 +VERTEX3 1289 84.3793 -17.4774 -17.7173 0.0331607 -0.0338576 -0.449023 +VERTEX3 1290 87.2308 -15.8191 -17.4931 0.0101578 -0.0254895 -0.454049 +VERTEX3 1291 90.3805 -13.814 -17.929 0.0103168 -0.00450789 -0.458284 +VERTEX3 1292 92.8791 -11.9297 -18.307 0.0044327 0.0120635 -0.403689 +VERTEX3 1293 95.5848 -7.65435 -18.766 0.0171867 0.0163565 -0.36335 +VERTEX3 1294 97.8382 -4.35542 -19.1603 0.032991 0.0368721 -0.320033 +VERTEX3 1295 99.3616 1.15439 -19.3178 0.0469868 0.0230926 -0.275714 +VERTEX3 1296 100.461 6.37476 -19.3728 0.0630318 0.0188934 -0.200638 +VERTEX3 1297 101.043 11.8194 -19.0524 0.0421192 -0.00527413 -0.14787 +VERTEX3 1298 101.315 17.6241 -19.0168 0.000303335 -0.00165028 -0.100188 +VERTEX3 1299 101.425 23.9219 -19.221 -0.0265959 0.00511864 -0.0519599 +VERTEX3 1300 101.283 30.8625 -19.8178 -0.0532187 0.0323724 -0.0135793 +VERTEX3 1301 100.408 36.9034 -19.7367 -0.0221237 0.0259656 0.0488794 +VERTEX3 1302 99.0533 42.5839 -19.588 0.00417551 0.0133585 0.0961228 +VERTEX3 1303 97.5133 47.9993 -19.3305 0.00870615 -0.00463965 0.141514 +VERTEX3 1304 95.5213 52.9892 -19.2643 0.00160894 -0.0120312 0.184391 +VERTEX3 1305 93.7395 59.9752 -19.2817 -0.00428006 -0.0390388 0.230267 +VERTEX3 1306 91.7936 64.3215 -19.4239 -0.0193926 -0.0471674 0.246231 +VERTEX3 1307 89.7473 68.3839 -19.7273 -0.0155656 -0.0496626 0.276215 +VERTEX3 1308 87.1195 73.3173 -20.0351 -0.0270417 -0.0292455 0.310668 +VERTEX3 1309 85.9587 75.5201 -20.5774 -0.0405061 -0.0308533 0.315621 +VERTEX3 1310 82.4419 81.1381 -20.7155 -0.0257659 -0.00674696 0.367027 +VERTEX3 1311 80.3529 82.252 -20.366 -0.0139368 0.00826526 0.366177 +VERTEX3 1312 77.1359 86.5127 -20.0988 0.00347965 0.0351286 0.392889 +VERTEX3 1313 76.5156 86.4944 -19.8553 0.0238729 0.025273 0.402659 +VERTEX3 1314 75.2368 86.1415 -19.6173 0.00553657 0.0377597 0.369154 +VERTEX3 1315 76.263 82.6352 -19.7841 0.00535766 0.0316811 0.347463 +VERTEX3 1316 75.7055 86.6126 -18.4933 0.00582403 0.000440815 0.356588 +VERTEX3 1317 76.2845 84.4133 -18.8272 0.00932038 -0.00719141 0.34242 +VERTEX3 1318 78.4283 76.7918 -19.1619 0.0271662 -0.020743 0.342292 +VERTEX3 1319 79.8705 64.7422 -20.6589 -0.0353287 0.000272578 0.296196 +VERTEX3 1320 78.9279 62.2205 -19.4752 -0.00550534 -0.0139921 0.361319 +VERTEX3 1321 78.7001 51.1252 -20.1725 -0.0212203 -0.00554888 0.314568 +VERTEX3 1322 79.8174 42.1094 -19.5503 -0.00784157 -0.0399082 0.313338 +VERTEX3 1323 79.3245 33.7398 -19.9575 -0.0209771 0.0309024 0.275647 +VERTEX3 1324 76.7663 8.38749 -19.9387 0.0127331 0.00531526 0.1793 +VERTEX3 1325 75.403 -8.50678 -20.0295 0.0291059 -0.00195436 0.151744 +VERTEX3 1326 75.1101 -16.6737 -20.0672 0.0119601 0.0119183 0.171307 +VERTEX3 1327 70.4915 -22.4119 -19.3448 0.00772829 -0.0171968 0.006875 +VERTEX3 1328 70.5473 -24.1169 -19.6299 -0.0400066 0.0424437 0.235709 +VERTEX3 1329 68.5609 -27.4756 -20.4098 -0.143228 -0.0199764 0.100668 +VERTEX3 1330 70.2572 -23.2097 -21.3117 0.0114816 -0.0520322 -0.0594078 +VERTEX3 1331 69.4773 -24.1567 -22.628 0.223018 0.0711652 -0.137354 +VERTEX3 1332 70.519 -25.645 -21.8848 0.0630278 -0.0224552 -0.27251 +VERTEX3 1333 70.028 -26.7984 -23.0378 0.0521477 -0.0318274 -0.372528 +VERTEX3 1334 73.4555 -22.466 -23.2433 0.0574713 -0.055085 -0.346844 +VERTEX3 1335 73.7371 -22.1879 -23.5571 0.0824985 -0.0760087 -0.380702 +VERTEX3 1336 74.4275 -23.8008 -23.8412 0.0677453 -0.0776483 -0.472208 +VERTEX3 1337 76.1327 -21.9057 -23.6339 0.061827 -0.0321065 -0.500497 +VERTEX3 1338 79.915 -19.7609 -23.1794 0.0332315 -0.0375082 -0.458649 +VERTEX3 1339 82.2882 -18.5526 -22.7836 0.0118466 -0.0168059 -0.475353 +VERTEX3 1340 85.5458 -15.2193 -23.2839 0.0103312 -0.00511828 -0.47318 +VERTEX3 1341 88.2855 -12.4578 -23.5063 -0.0071372 0.013722 -0.424944 +VERTEX3 1342 90.7416 -10.8002 -24.0646 -0.000726261 0.0254574 -0.417428 +VERTEX3 1343 93.5212 -6.62188 -24.5628 0.0246902 0.0403493 -0.3592 +VERTEX3 1344 95.1479 -3.26831 -25.0228 0.042963 0.0393222 -0.336746 +VERTEX3 1345 97.1451 2.803 -24.9967 0.0567076 0.0257069 -0.248615 +VERTEX3 1346 98.0553 6.96242 -24.689 0.0547455 -0.00422754 -0.203856 +VERTEX3 1347 98.6139 12.3551 -24.4809 0.0284504 -0.0188159 -0.16331 +VERTEX3 1348 99.1425 18.5453 -24.5342 -0.00855181 -0.0177912 -0.113689 +VERTEX3 1349 99.2859 25.0951 -24.9369 -0.0394976 -0.00230053 -0.0774991 +VERTEX3 1350 99.1934 31.3636 -25.3675 -0.0635576 0.0150663 -0.029258 +VERTEX3 1351 98.5343 37.3796 -25.512 -0.0334968 0.027031 0.0253742 +VERTEX3 1352 97.4745 43.4306 -25.3384 -0.0114219 0.019827 0.0815107 +VERTEX3 1353 95.9164 48.9811 -25.1712 0.0078121 0.00796862 0.125119 +VERTEX3 1354 94.1486 53.8575 -25.0348 0.0026573 -0.0115853 0.171036 +VERTEX3 1355 92.0286 58.4139 -24.9997 -0.00249795 -0.0173898 0.211496 +VERTEX3 1356 90.0836 65.8756 -25.1693 -0.0142972 -0.0478136 0.262619 +VERTEX3 1357 88.2566 68.3545 -25.5241 -0.0259652 -0.0423123 0.265946 +VERTEX3 1358 86.0228 72.6682 -25.762 -0.0216215 -0.047334 0.299699 +VERTEX3 1359 83.4822 75.4046 -26.0334 -0.0341828 -0.0288618 0.321779 +VERTEX3 1360 81.9022 80.6545 -26.7792 -0.0459437 -0.0223319 0.33828 +VERTEX3 1361 78.7139 83.7704 -26.834 -0.025886 -0.00030478 0.383787 +VERTEX3 1362 76.8536 86.901 -26.1386 -0.0213267 0.0142978 0.379751 +VERTEX3 1363 74.3345 89.9396 -25.8483 0.00431052 0.0439694 0.400729 +VERTEX3 1364 73.3193 89.0602 -25.5207 0.0236476 0.0296516 0.413848 +VERTEX3 1365 72.8997 88.4662 -25.1117 -0.000823544 0.0441112 0.368777 +VERTEX3 1366 73.4024 85.7139 -25.3084 0.0100271 0.0364887 0.351837 +VERTEX3 1367 72.5856 89.2706 -24.0012 0.00576697 0.00594832 0.371969 +VERTEX3 1368 74.2332 84.9363 -24.5306 0.0138638 0.0074292 0.339855 +VERTEX3 1369 76.5277 75.714 -24.9532 0.0233447 -0.00661115 0.342878 +VERTEX3 1370 78.1913 65.4724 -26.1779 -0.031716 0.0154709 0.306381 +VERTEX3 1371 77.2495 61.9924 -25.27 -0.00379662 -0.0124099 0.35377 +VERTEX3 1372 77.3383 50.767 -25.6826 -0.0209697 -0.00118228 0.312195 +VERTEX3 1373 79.1097 42.0622 -25.2066 0.0130806 -0.0343648 0.304086 +VERTEX3 1374 78.1268 25.5176 -25.577 0.0309944 -0.0119889 0.206391 +VERTEX3 1375 75.8766 6.83724 -25.5522 -0.00760425 0.0143067 0.0794913 +VERTEX3 1376 75.5187 -8.84063 -25.7064 0.0269143 -0.00958516 0.26088 +VERTEX3 1377 74.1222 -21.818 -25.7371 -0.0025662 0.00917756 0.156186 +VERTEX3 1378 69.2992 -29.4657 -25.294 -0.0127597 -0.015665 0.143207 +VERTEX3 1379 69.7248 -25.2439 -26.8396 0.0274069 -0.0351142 0.224327 +VERTEX3 1380 69.3694 -22.7413 -27.9067 0.0133123 -0.15812 0.17486 +VERTEX3 1381 67.9744 -25.3842 -27.1695 0.0708595 -0.0328513 -0.155685 +VERTEX3 1382 67.0122 -25.7192 -28.0365 0.0249375 0.176853 -0.326856 +VERTEX3 1383 70.2703 -23.0832 -28.7005 0.0631188 -0.0267923 -0.331509 +VERTEX3 1384 70.616 -22.3494 -28.9414 0.0884913 -0.0559426 -0.35865 +VERTEX3 1385 71.2981 -23.2486 -29.0055 0.0643955 -0.0645951 -0.444657 +VERTEX3 1386 72.0034 -22.0017 -28.9124 0.0678631 -0.0166746 -0.478628 +VERTEX3 1387 75.6536 -21.5335 -28.7126 0.0358616 -0.0428282 -0.479667 +VERTEX3 1388 77.5055 -18.3072 -28.1804 0.0133852 -0.0162659 -0.482668 +VERTEX3 1389 80.4772 -17.5712 -28.4667 0.00959993 -0.0121629 -0.498398 +VERTEX3 1390 82.9138 -14.9443 -28.5427 -0.0236725 0.00714229 -0.458885 +VERTEX3 1391 85.6555 -12.13 -29.2649 -0.00823902 0.0243446 -0.433283 +VERTEX3 1392 88.651 -9.86972 -29.8163 0.0069994 0.040044 -0.410604 +VERTEX3 1393 90.547 -6.27145 -30.373 0.0328122 0.0408231 -0.381344 +VERTEX3 1394 92.7285 -1.63219 -30.566 0.0597995 0.0336122 -0.310953 +VERTEX3 1395 94.2839 3.59208 -30.3074 0.0605617 0.0059707 -0.246835 +VERTEX3 1396 95.1085 8.03284 -30.0544 0.0590874 -0.0179465 -0.219276 +VERTEX3 1397 95.9138 13.5782 -29.8927 0.0189336 -0.0383062 -0.179774 +VERTEX3 1398 96.4507 19.6802 -30.0322 -0.0218806 -0.026314 -0.132146 +VERTEX3 1399 96.7889 25.8164 -30.4303 -0.0523149 -0.0185321 -0.0883789 +VERTEX3 1400 96.824 31.8195 -30.9362 -0.0416177 0.00646906 -0.0261174 +VERTEX3 1401 96.1451 37.4629 -30.9588 -0.0383565 0.0203326 0.00735733 +VERTEX3 1402 95.158 43.3953 -30.9547 -0.0193734 0.0227557 0.0661056 +VERTEX3 1403 93.7444 48.7313 -30.8208 -0.00793037 0.0153917 0.106667 +VERTEX3 1404 92.1278 54.6759 -30.706 0.0105422 0.00205355 0.154034 +VERTEX3 1405 90.2937 59.8412 -30.5344 0.000514297 -0.0203848 0.201394 +VERTEX3 1406 87.958 64.9758 -30.809 -0.00484595 -0.0269136 0.244687 +VERTEX3 1407 86.0955 71.2584 -30.9911 -0.0277449 -0.0482068 0.291444 +VERTEX3 1408 84.1426 73.0053 -31.4141 -0.0329671 -0.0409192 0.28922 +VERTEX3 1409 82.2472 77.5983 -31.8511 -0.0315614 -0.0426421 0.326738 +VERTEX3 1410 79.6371 79.9707 -32.0474 -0.0406592 -0.0293542 0.33505 +VERTEX3 1411 78.1062 84.407 -32.6634 -0.0482315 -0.0121693 0.361296 +VERTEX3 1412 75.1183 86.6696 -32.6148 -0.029536 0.00605543 0.395925 +VERTEX3 1413 73.308 89.0894 -31.8535 -0.0227556 0.0232596 0.394914 +VERTEX3 1414 71.2955 89.7274 -31.4354 0.00303822 0.0543128 0.406308 +VERTEX3 1415 69.787 91.5569 -30.8555 0.0291562 0.0314514 0.418447 +VERTEX3 1416 69.7671 90.2587 -30.6632 0.0037346 0.0477577 0.379247 +VERTEX3 1417 69.7269 88.787 -30.5953 0.0116304 0.0419974 0.360568 +VERTEX3 1418 70.3176 89.2417 -29.4754 0.00972371 0.0176884 0.369921 +VERTEX3 1419 71.4472 86.3016 -30.0195 0.0208826 0.0297319 0.339483 +VERTEX3 1420 73.7578 74.4881 -30.6095 0.0237172 0.00552682 0.346719 +VERTEX3 1421 75.0753 66.1264 -31.6354 -0.0392941 0.0236057 0.308146 +VERTEX3 1422 75.863 62.0432 -30.6028 -0.0130147 -0.010823 0.322768 +VERTEX3 1423 75.2829 54.8412 -31.2213 -0.0173902 0.00609504 0.304494 +VERTEX3 1424 78.1937 43.0889 -30.6846 0.00705521 0.0228965 0.198947 +VERTEX3 1425 77.9607 26.5737 -30.9792 -0.0267162 -0.0210202 0.111681 +VERTEX3 1426 76.7212 12.181 -30.9087 -0.00993802 0.00211786 0.154679 +VERTEX3 1427 74.1408 -6.45782 -31.5739 0.0240627 0.0152098 0.179241 +VERTEX3 1428 72.6978 -21.9769 -31.8933 -0.0141232 -0.00244169 0.116764 +VERTEX3 1429 67.6314 -29.8428 -30.9745 -0.00249805 0.00541729 0.00396337 +VERTEX3 1430 66.7463 -29.6754 -32.5291 0.00971802 0.000361179 0.128907 +VERTEX3 1431 65.4271 -25.0572 -33.1542 0.0926776 -0.0804334 0.0928079 +VERTEX3 1432 67.2575 -22.9298 -33.4803 0.0615321 0.0144616 -0.21238 +VERTEX3 1433 66.4936 -22.0665 -33.6761 -0.0333907 0.0360579 -0.366224 +VERTEX3 1434 67.3936 -23.3629 -34.0999 0.0398032 -0.0398812 -0.392117 +VERTEX3 1435 68.1639 -21.1797 -34.2554 0.051015 -0.00698637 -0.458979 +VERTEX3 1436 71.174 -22.2207 -34.0169 0.0356906 -0.0391033 -0.47758 +VERTEX3 1437 72.8035 -19.157 -33.388 0.00785402 -0.00510342 -0.483534 +VERTEX3 1438 75.2985 -18.4456 -33.7809 0.00621085 -0.0205892 -0.510805 +VERTEX3 1439 77.1405 -16.7445 -33.5028 -0.0289752 -0.000752808 -0.476324 +VERTEX3 1440 80.0987 -14.3355 -34.1896 -0.0238553 0.0209735 -0.461372 +VERTEX3 1441 82.8013 -13.1957 -34.7851 -0.0195396 0.0276134 -0.45019 +VERTEX3 1442 85.5539 -7.49551 -35.3843 0.0205829 0.0359955 -0.410974 +VERTEX3 1443 87.7944 -4.50207 -35.7542 0.0502611 0.0474093 -0.365888 +VERTEX3 1444 89.8272 0.717651 -35.7664 0.0735168 0.0186221 -0.292078 +VERTEX3 1445 90.9904 4.41165 -35.592 0.0652191 -0.0100662 -0.260011 +VERTEX3 1446 91.9443 9.38018 -35.3157 0.0546525 -0.0410433 -0.241549 +VERTEX3 1447 92.8547 15.0717 -35.2712 0.00368378 -0.0458927 -0.180592 +VERTEX3 1448 93.5937 20.8523 -35.4278 -0.0226035 -0.0371043 -0.132394 +VERTEX3 1449 93.912 26.3331 -35.907 -0.033033 -0.0278691 -0.101234 +VERTEX3 1450 93.9694 32.2258 -36.2281 -0.0327045 0.00789771 -0.0473936 +VERTEX3 1451 93.4517 37.7881 -36.391 -0.0202188 0.0195613 0.000174701 +VERTEX3 1452 92.4319 43.5283 -36.2987 -0.0215584 0.0204936 0.0348913 +VERTEX3 1453 91.3003 49.3211 -36.2367 -0.00383684 0.0187722 0.104374 +VERTEX3 1454 89.6363 53.9764 -36.0828 -0.00380787 0.0120067 0.134683 +VERTEX3 1455 87.8037 59.713 -36.0672 0.00968017 -0.00293164 0.178328 +VERTEX3 1456 85.8238 64.3053 -36.0608 -0.000689511 -0.0294747 0.230969 +VERTEX3 1457 83.5159 70.4977 -36.4274 -0.0090868 -0.0379646 0.281395 +VERTEX3 1458 81.6597 74.2725 -36.7412 -0.0279386 -0.0403392 0.304868 +VERTEX3 1459 79.7716 77.3602 -37.2666 -0.0426384 -0.0386008 0.316639 +VERTEX3 1460 77.6781 81.2863 -37.6305 -0.0393752 -0.0340383 0.351231 +VERTEX3 1461 75.341 84.0647 -37.8212 -0.0447329 -0.0160148 0.362526 +VERTEX3 1462 74.4442 87.1637 -38.4902 -0.0524327 -0.00441544 0.379999 +VERTEX3 1463 71.3904 88.4898 -38.2795 -0.0341535 0.0141816 0.415028 +VERTEX3 1464 69.3312 91.2277 -37.2906 -0.0216433 0.0321534 0.408703 +VERTEX3 1465 67.0577 93.0302 -36.8122 0.012206 0.0592892 0.426359 +VERTEX3 1466 65.8319 94.8326 -36.3225 0.0333656 0.0326046 0.432775 +VERTEX3 1467 66.1824 92.3533 -35.9384 0.00310777 0.0479104 0.384037 +VERTEX3 1468 67.4996 87.779 -35.9754 0.00928708 0.0501685 0.369739 +VERTEX3 1469 67.3733 88.5294 -34.8014 0.0248913 0.0311666 0.367688 +VERTEX3 1470 68.9776 84.4395 -35.2169 0.0196048 0.051194 0.351823 +VERTEX3 1471 70.9904 74.7676 -35.8206 0.0150734 0.0166876 0.335095 +VERTEX3 1472 72.4621 66.5139 -36.662 -0.040102 0.032325 0.308628 +VERTEX3 1473 73.2169 60.8857 -35.8399 -0.0141627 -0.00604112 0.308299 +VERTEX3 1474 72.9717 56.383 -36.4601 -0.0116308 0.000800865 0.284443 +VERTEX3 1475 76.8823 42.1512 -35.9493 -0.0166959 -0.0225436 0.165209 +VERTEX3 1476 76.3364 29.3476 -36.5345 0.0139248 -0.034737 0.143234 +VERTEX3 1477 74.963 17.019 -36.5036 -0.000772206 0.00471935 0.169186 +VERTEX3 1478 72.6542 -4.9166 -36.9487 0.030794 -0.00361164 0.156656 +VERTEX3 1479 70.9178 -20.3618 -37.4833 0.0217225 -0.0397358 0.069246 +VERTEX3 1480 64.8818 -26.3958 -36.3331 0.0122885 0.0165145 -0.0369337 +VERTEX3 1481 64.8909 -22.5536 -38.3766 0.0496567 0.0212276 -0.0352648 +VERTEX3 1482 63.8705 -22.2005 -37.8756 0.0320127 0.0338142 -0.0407457 +VERTEX3 1483 64.0589 -23.3015 -38.6045 0.0217371 0.0136269 -0.291723 +VERTEX3 1484 64.155 -23.4411 -39.0591 0.0114174 -0.0820904 -0.432983 +VERTEX3 1485 66.7899 -22.9587 -39.0253 0.0133064 -0.0294094 -0.414646 +VERTEX3 1486 67.745 -19.7986 -38.4394 0.00968615 -0.00384322 -0.458981 +VERTEX3 1487 70.2388 -17.6577 -38.8163 0.00908037 -0.0330107 -0.495141 +VERTEX3 1488 71.8437 -17.8684 -38.354 -0.0229907 -0.0116344 -0.491994 +VERTEX3 1489 74.434 -16.4085 -38.9162 -0.0279992 0.0111495 -0.474053 +VERTEX3 1490 77.5076 -12.1651 -39.6007 -0.0219847 0.0114424 -0.447458 +VERTEX3 1491 79.6457 -9.35047 -40.2263 -0.00723005 0.0335816 -0.43607 +VERTEX3 1492 82.4631 -6.18508 -40.776 0.0285012 0.0466896 -0.404587 +VERTEX3 1493 84.4667 -3.00146 -40.9737 0.0735362 0.0359303 -0.337655 +VERTEX3 1494 86.2617 1.58491 -40.9146 0.0647485 0.00844629 -0.299086 +VERTEX3 1495 87.4412 5.80572 -40.7444 0.0778222 -0.0240954 -0.292836 +VERTEX3 1496 88.6216 11.0578 -40.4579 0.0273573 -0.0456696 -0.221676 +VERTEX3 1497 89.5603 16.1545 -40.512 0.00677166 -0.0577759 -0.19126 +VERTEX3 1498 90.1296 21.3822 -40.729 -0.012784 -0.0524927 -0.161613 +VERTEX3 1499 90.7726 27.0133 -41.1119 -0.028196 -0.0187793 -0.104133 +VERTEX3 1500 90.6504 32.4456 -41.5362 0.00974103 0.00644344 -0.0665111 +VERTEX3 1501 90.1924 38.0363 -41.5816 -0.0115209 0.00482246 -0.0183163 +VERTEX3 1502 89.4655 43.7608 -41.5566 -0.00745852 0.0205168 0.039763 +VERTEX3 1503 88.2373 49.3497 -41.4436 0.00275464 0.0165505 0.0750216 +VERTEX3 1504 86.7563 54.5414 -41.2932 0.00413368 0.0138075 0.132955 +VERTEX3 1505 85.1674 59.6311 -41.2783 0.00904693 0.00359723 0.173624 +VERTEX3 1506 83.1429 64.669 -41.2271 0.0130311 -0.011177 0.211844 +VERTEX3 1507 81.0834 70.3497 -41.2255 0.00334403 -0.0395699 0.263313 +VERTEX3 1508 78.8343 74.5378 -41.837 -0.0170524 -0.036409 0.306685 +VERTEX3 1509 76.9704 78.2887 -42.2503 -0.0331141 -0.0333555 0.331987 +VERTEX3 1510 75.2054 80.7248 -42.9092 -0.0435674 -0.0367561 0.344026 +VERTEX3 1511 72.6188 86.2679 -43.0253 -0.0485311 -0.0250179 0.372545 +VERTEX3 1512 70.6295 88.4758 -43.3962 -0.0506844 -0.00140851 0.39131 +VERTEX3 1513 70.0415 89.3238 -44.0338 -0.0567597 0.00143673 0.397717 +VERTEX3 1514 67.0893 92.4475 -43.6743 -0.0334864 0.0238809 0.431566 +VERTEX3 1515 64.7998 92.7336 -42.6753 -0.0147136 0.0404554 0.423831 +VERTEX3 1516 62.0483 97.2257 -41.7662 0.0185617 0.0590311 0.443489 +VERTEX3 1517 62.1762 95.2864 -41.4949 0.0362763 0.0328954 0.442675 +VERTEX3 1518 61.5057 93.9803 -41.0312 0.0117039 0.0487058 0.402903 +VERTEX3 1519 63.1576 92.8176 -40.9474 0.0137075 0.0533245 0.393667 +VERTEX3 1520 63.5069 89.4044 -39.9268 0.0392544 0.0384033 0.377802 +VERTEX3 1521 65.5795 84.3928 -40.2234 0.0159522 0.0606865 0.374846 +VERTEX3 1522 67.9504 74.881 -40.7915 -0.0052072 0.0299281 0.312824 +VERTEX3 1523 69.1993 67.8689 -41.7627 -0.0231658 0.0149076 0.307748 +VERTEX3 1524 69.4518 64.4947 -40.922 0.00826868 -0.00872438 0.321109 +VERTEX3 1525 69.9314 57.0487 -41.6044 0.0601814 -0.00742069 0.333947 +VERTEX3 1526 73.1128 39.6102 -41.3803 0.0313457 -0.0270637 0.326901 +VERTEX3 1527 73.816 33.9347 -41.8335 0.0368638 -0.0580909 0.228645 +VERTEX3 1528 71.8484 11.838 -41.875 0.00187991 -0.00694296 0.149076 +VERTEX3 1529 68.9599 -7.76811 -42.4075 0.0301345 0.00937665 0.105541 +VERTEX3 1530 69.0249 -19.0142 -42.9454 0.0340705 -0.0319851 0.00458727 +VERTEX3 1531 60.4047 -23.7862 -41.3963 0.0524904 0.043109 -0.293497 +VERTEX3 1532 61.9664 -23.441 -43.0317 -0.0269563 0.0579514 -0.122643 +VERTEX3 1533 60.8664 -23.5713 -42.8119 -0.039173 0.0372099 -0.097467 +VERTEX3 1534 62.6175 -21.9478 -43.6007 -0.0107893 0.0156774 -0.243175 +VERTEX3 1535 63.3952 -20.4979 -43.5802 0.10752 -0.062379 -0.351754 +VERTEX3 1536 65.3089 -19.8889 -43.6383 0.0188405 -0.0275393 -0.443048 +VERTEX3 1537 66.1896 -18.2747 -43.1642 -0.00992678 -0.0228956 -0.48091 +VERTEX3 1538 69.1522 -15.3075 -43.7994 -0.0226127 -0.00113957 -0.467901 +VERTEX3 1539 71.8914 -13.0369 -44.1099 -0.0267934 -0.0101685 -0.447369 +VERTEX3 1540 74.0138 -9.81389 -44.8021 -0.0117699 0.0103916 -0.450975 +VERTEX3 1541 76.3878 -8.63215 -45.5268 0.00955247 0.0323776 -0.44717 +VERTEX3 1542 79.0051 -4.45005 -45.8084 0.0417157 0.037963 -0.363136 +VERTEX3 1543 80.6544 -0.985547 -45.9746 0.0552245 0.0244523 -0.345563 +VERTEX3 1544 82.3479 3.44551 -45.955 0.0807357 -0.00578394 -0.329279 +VERTEX3 1545 83.5474 7.57172 -45.5453 0.0564404 -0.035608 -0.26663 +VERTEX3 1546 84.7522 11.6749 -45.5049 0.0370355 -0.0643527 -0.253696 +VERTEX3 1547 85.5967 17.0407 -45.5306 0.00924211 -0.066065 -0.211407 +VERTEX3 1548 86.6575 22.2161 -45.8742 -0.0155821 -0.0421759 -0.162294 +VERTEX3 1549 87.0036 27.4286 -46.2157 -0.00651994 -0.0277934 -0.139081 +VERTEX3 1550 87.0431 32.741 -46.5636 0.0506177 -0.0115966 -0.0888988 +VERTEX3 1551 86.7316 38.3438 -46.5432 0.00997907 -0.000602856 -0.0336428 +VERTEX3 1552 86.0127 43.946 -46.6595 0.0102262 0.00482278 0.026331 +VERTEX3 1553 84.8687 49.5182 -46.5006 0.00800615 0.0178503 0.0671717 +VERTEX3 1554 83.4624 54.7969 -46.3385 0.0215592 0.00774776 0.11422 +VERTEX3 1555 81.8702 59.758 -46.1448 0.0164729 0.0112076 0.163042 +VERTEX3 1556 80.1483 64.5699 -46.1701 0.0150514 -0.00696872 0.209347 +VERTEX3 1557 78.1347 69.3005 -46.1619 0.0211841 -0.01813 0.242827 +VERTEX3 1558 76.0457 75.0519 -46.307 0.00119785 -0.0449532 0.290414 +VERTEX3 1559 73.8076 79.1733 -47.161 -0.023604 -0.0451409 0.34156 +VERTEX3 1560 72.1729 81.2573 -47.6044 -0.0386634 -0.034443 0.358967 +VERTEX3 1561 70.2429 83.0558 -48.1462 -0.0438765 -0.0313977 0.361136 +VERTEX3 1562 67.9455 87.5354 -48.3964 -0.0493049 -0.0164865 0.396091 +VERTEX3 1563 65.7726 89.333 -48.6702 -0.0545475 0.00176637 0.406749 +VERTEX3 1564 65.3508 92.6897 -49.6827 -0.056951 0.0148531 0.422295 +VERTEX3 1565 62.5012 95.1066 -48.8092 -0.0334693 0.0318517 0.448826 +VERTEX3 1566 60.2425 94.9023 -47.7367 -0.018932 0.0460175 0.434654 +VERTEX3 1567 58.2074 98.535 -46.9354 0.0232097 0.0637755 0.456122 +VERTEX3 1568 58.2205 93.4584 -46.6027 0.0353268 0.0310175 0.445409 +VERTEX3 1569 57.0309 94.8645 -46.0578 0.0125333 0.0508423 0.410386 +VERTEX3 1570 59.4046 90.3547 -45.7076 0.0131228 0.0572616 0.404577 +VERTEX3 1571 59.9908 87.3313 -44.5548 0.0453813 0.0387983 0.388478 +VERTEX3 1572 61.1953 86.2104 -44.8249 0.0155927 0.0556547 0.402045 +VERTEX3 1573 64.5191 71.271 -45.6235 -0.038489 0.0417302 0.287886 +VERTEX3 1574 65.9231 68.393 -46.4579 0.0315401 -0.00898587 0.311249 +VERTEX3 1575 66.6109 66.2246 -45.6938 0.0982034 -0.0244743 0.360901 +VERTEX3 1576 66.0301 60.6619 -46.3939 0.0604048 -0.0129078 0.453147 +VERTEX3 1577 69.2244 50.0548 -46.0686 0.0511843 -0.0350808 0.358729 +VERTEX3 1578 70.953 33.951 -46.9949 0.0408667 -0.0530907 0.242033 +VERTEX3 1579 68.0135 12.4102 -47.0225 -0.00033589 -0.017148 0.134823 +VERTEX3 1580 65.1657 -3.74171 -47.325 0.023265 -0.000811127 0.070539 +VERTEX3 1581 65.6787 -17.988 -47.8933 0.0378558 -0.0237926 -0.0403539 +VERTEX3 1582 57.9155 -22.851 -46.3846 0.0627694 0.0476114 -0.298624 +VERTEX3 1583 60.4012 -23.8006 -48.0722 -0.0175409 0.0405722 -0.0937199 +VERTEX3 1584 60.9663 -23.5908 -48.1829 -0.062876 0.0189939 -0.0496778 +VERTEX3 1585 61.1276 -20.5712 -48.6701 -0.0178985 -0.00666239 -0.304668 +VERTEX3 1586 61.2104 -19.4996 -48.0108 0.0512212 -0.0121056 -0.481076 +VERTEX3 1587 63.5276 -15.749 -48.5364 -0.000159891 0.00092903 -0.440198 +VERTEX3 1588 65.9498 -15.1022 -48.633 -0.0193073 -0.0238762 -0.444414 +VERTEX3 1589 67.7228 -12.5174 -49.3539 -0.0425397 0.00319549 -0.490492 +VERTEX3 1590 70.0327 -9.94011 -50.0068 0.000240103 0.00720765 -0.47477 +VERTEX3 1591 73.0252 -6.24211 -50.317 0.01905 0.040978 -0.398292 +VERTEX3 1592 74.7622 -2.46746 -50.6494 0.0345091 0.0271332 -0.37735 +VERTEX3 1593 76.7075 1.6127 -50.8283 0.0680304 0.0117515 -0.364232 +VERTEX3 1594 78.2718 5.31932 -50.6004 0.063757 -0.022457 -0.298487 +VERTEX3 1595 79.4207 8.61003 -50.4364 0.0553205 -0.0497188 -0.296582 +VERTEX3 1596 80.3699 12.6642 -50.2663 0.0372382 -0.0764539 -0.284692 +VERTEX3 1597 81.8456 17.7424 -50.5004 0.00120569 -0.0597593 -0.221021 +VERTEX3 1598 82.5677 23.0228 -50.7938 -0.00368701 -0.0523462 -0.194979 +VERTEX3 1599 83.1467 28.0163 -51.3426 0.0264985 -0.0276392 -0.150217 +VERTEX3 1600 83.083 33.2442 -51.3508 0.071062 -0.0274328 -0.119475 +VERTEX3 1601 82.9376 38.7775 -51.3289 0.034942 -0.00911516 -0.0555139 +VERTEX3 1602 82.2223 44.047 -51.4787 0.0199511 0.00031195 0.0078893 +VERTEX3 1603 81.235 49.8355 -51.4378 0.0225789 0.00783699 0.0693072 +VERTEX3 1604 79.8098 55.2067 -51.1796 0.0305873 0.0144443 0.118577 +VERTEX3 1605 78.1332 59.7655 -50.9493 0.0345899 0.00689298 0.149462 +VERTEX3 1606 76.4592 64.4058 -50.7958 0.0293862 -0.00051899 0.195062 +VERTEX3 1607 74.7561 69.0161 -50.8706 0.0134262 -0.0119253 0.234279 +VERTEX3 1608 72.7954 73.3398 -50.8495 0.0212072 -0.0251977 0.273053 +VERTEX3 1609 70.9188 78.5322 -51.1866 -0.00511357 -0.0468202 0.314757 +VERTEX3 1610 68.0514 83.316 -52.1482 -0.031432 -0.0533178 0.372687 +VERTEX3 1611 66.5279 86.1676 -52.5791 -0.0500573 -0.03711 0.388967 +VERTEX3 1612 64.809 86.7991 -53.2007 -0.0541831 -0.0246155 0.388138 +VERTEX3 1613 62.9225 89.5577 -53.5741 -0.051962 -0.00485298 0.423703 +VERTEX3 1614 61.556 90.637 -53.8707 -0.0561293 0.00796829 0.428079 +VERTEX3 1615 60.6739 93.5791 -54.7538 -0.0592086 0.0210413 0.440965 +VERTEX3 1616 57.9844 95.6453 -53.8787 -0.0381556 0.0385851 0.461591 +VERTEX3 1617 55.2106 96.1563 -52.4626 -0.0139746 0.0527838 0.454671 +VERTEX3 1618 53.9497 98.1681 -51.8105 0.0282638 0.0625585 0.464345 +VERTEX3 1619 53.9363 95.4543 -51.3244 0.0419894 0.0301883 0.468353 +VERTEX3 1620 52.8747 94.844 -50.6344 0.0101632 0.0561052 0.42219 +VERTEX3 1621 55.8505 87.8868 -49.9376 0.016767 0.0616231 0.420459 +VERTEX3 1622 55.8146 89.0563 -48.7483 0.0434447 0.0215768 0.384589 +VERTEX3 1623 57.8895 81.2073 -49.3424 0.050625 0.020892 0.446723 +VERTEX3 1624 60.1648 73.7911 -50.2444 0.171415 -0.0559134 0.424003 +VERTEX3 1625 61.2856 67.6605 -51.2386 0.0556166 -0.0382272 0.416263 +VERTEX3 1626 62.2855 64.783 -50.6363 0.0913669 -0.0483881 0.478669 +VERTEX3 1627 60.7017 61.8075 -51.2552 0.0615943 -0.0212416 0.440049 +VERTEX3 1628 64.5343 53.0613 -50.9176 0.0590381 -0.04557 0.36518 +VERTEX3 1629 66.2934 36.188 -51.9737 0.0464774 -0.0487828 0.249114 +VERTEX3 1630 64.6643 17.0237 -51.9552 -0.0039024 -0.0276437 0.128314 +VERTEX3 1631 62.648 0.502743 -52.2198 0.0167538 -0.00590928 0.0617311 +VERTEX3 1632 62.1568 -16.1515 -52.8663 0.0212865 -0.018424 -0.0779923 +VERTEX3 1633 55.8008 -21.5124 -51.6047 0.0494936 0.0525557 -0.320453 +VERTEX3 1634 57.9108 -24.1961 -52.8426 -0.0174842 0.0200288 -0.101986 +VERTEX3 1635 58.0568 -20.8858 -52.8774 -0.0278663 0.0113851 -0.0728 +VERTEX3 1636 58.3775 -17.6467 -53.1316 -0.00907174 -0.0196403 -0.319869 +VERTEX3 1637 60.4528 -14.1464 -52.8378 0.0114437 0.00874521 -0.491188 +VERTEX3 1638 62.1657 -12.2925 -53.6505 -0.0132846 0.00564484 -0.466092 +VERTEX3 1639 64.3023 -9.64571 -54.3088 0.00358489 -0.0251754 -0.447503 +VERTEX3 1640 66.9866 -6.94619 -54.5589 0.000746575 0.00937587 -0.399259 +VERTEX3 1641 68.7441 -3.8202 -54.948 0.0131459 0.0322259 -0.410645 +VERTEX3 1642 70.573 -0.708933 -55.4092 0.0430693 0.0190722 -0.388022 +VERTEX3 1643 72.1408 2.47028 -55.3981 0.0728895 -0.00588852 -0.345363 +VERTEX3 1644 73.6919 6.36997 -55.1771 0.0647471 -0.0350007 -0.33031 +VERTEX3 1645 74.9984 10.1176 -55.0305 0.0525586 -0.0736392 -0.30331 +VERTEX3 1646 76.3387 14.1691 -54.9958 0.0223109 -0.0749091 -0.275895 +VERTEX3 1647 77.3534 19.007 -55.1929 0.00207055 -0.0720503 -0.246173 +VERTEX3 1648 78.4068 23.8489 -55.8254 0.011039 -0.0399416 -0.206449 +VERTEX3 1649 78.925 28.8148 -56.0499 0.0442096 -0.0207818 -0.181131 +VERTEX3 1650 78.9242 33.9009 -56.0554 0.0770191 -0.021857 -0.12546 +VERTEX3 1651 78.7924 39.3736 -56.0194 0.0458866 -0.0219841 -0.0539153 +VERTEX3 1652 78.1815 44.582 -56.0909 0.026711 -0.0117767 -0.00516767 +VERTEX3 1653 77.0213 49.5617 -56.0946 0.0306011 0.00361666 0.0451139 +VERTEX3 1654 75.6695 54.6574 -55.9034 0.0391872 0.00831596 0.103864 +VERTEX3 1655 74.0377 59.39 -55.5877 0.0316699 -0.000177788 0.142361 +VERTEX3 1656 72.3066 64.1195 -55.3608 0.0420282 0.00568674 0.182937 +VERTEX3 1657 70.6785 69.065 -55.0893 0.0474014 -0.0138362 0.231972 +VERTEX3 1658 68.8495 73.6249 -55.1709 0.0269143 -0.0297898 0.272733 +VERTEX3 1659 66.96 77.3989 -55.2628 0.0149941 -0.0310161 0.299433 +VERTEX3 1660 65.1493 81.674 -55.7805 -0.0112689 -0.0488553 0.338859 +VERTEX3 1661 62.2549 85.2314 -56.9933 -0.0424886 -0.0420677 0.389157 +VERTEX3 1662 60.6726 87.5413 -57.522 -0.0531561 -0.0275884 0.407265 +VERTEX3 1663 59.367 89.4468 -58.1803 -0.0610866 -0.0190834 0.416218 +VERTEX3 1664 56.984 93.3002 -58.3441 -0.0619431 -0.00201218 0.449691 +VERTEX3 1665 54.9877 94.8247 -58.6055 -0.0659844 0.0243993 0.454672 +VERTEX3 1666 55.3147 96.0022 -59.4359 -0.0656131 0.0324148 0.464534 +VERTEX3 1667 52.3335 97.1347 -58.6571 -0.0419177 0.0432607 0.480069 +VERTEX3 1668 50.3584 97.5508 -57.0374 -0.00760617 0.0552772 0.477965 +VERTEX3 1669 49.5887 96.3877 -56.1715 0.0268199 0.0621249 0.471145 +VERTEX3 1670 49.749 95.3347 -55.9161 0.0537566 0.0306794 0.485664 +VERTEX3 1671 49.1487 95.2242 -54.9086 -0.00259879 0.0628461 0.42541 +VERTEX3 1672 50.0265 91.6156 -54.0854 0.0295514 0.0460888 0.439395 +VERTEX3 1673 51.5455 90.0031 -53.1189 0.0412057 -0.0177738 0.406468 +VERTEX3 1674 53.4036 83.6667 -53.37 0.124173 -0.104891 0.409794 +VERTEX3 1675 55.571 76.5196 -54.2349 0.163103 -0.1209 0.510145 +VERTEX3 1676 55.9986 68.7935 -55.9996 0.0557666 -0.0394882 0.466972 +VERTEX3 1677 56.9519 64.254 -55.7565 0.0929533 -0.0364926 0.433434 +VERTEX3 1678 55.8584 63.926 -55.8106 0.0668746 -0.0262408 0.433705 +VERTEX3 1679 60.5731 50.183 -56.0335 0.0549869 -0.0507677 0.319697 +VERTEX3 1680 61.9902 40.2031 -56.6253 0.0423343 -0.048869 0.251774 +VERTEX3 1681 62.026 25.8712 -56.7336 0.0123102 -0.0153988 0.139326 +VERTEX3 1682 59.1251 7.3394 -56.8448 0.0232372 -0.00415434 0.0773901 +VERTEX3 1683 59.3377 -10.1283 -57.4468 0.0193145 -0.012943 -0.0920053 +VERTEX3 1684 53.6737 -15.1773 -55.9065 0.030672 0.0454935 -0.299846 +VERTEX3 1685 55.2892 -22.9012 -57.3839 -0.0128868 -0.0021168 -0.110866 +VERTEX3 1686 55.7751 -17.5166 -57.475 -0.0300287 -2.33206e-06 -0.0998741 +VERTEX3 1687 56.3469 -13.4508 -57.7633 0.0107341 0.00187005 -0.346624 +VERTEX3 1688 58.3475 -10.75 -58.4112 -0.0169039 -0.0392486 -0.470037 +VERTEX3 1689 60.592 -8.79832 -58.5696 -0.00555821 -0.0156995 -0.41107 +VERTEX3 1690 62.3049 -5.1375 -58.9744 0.0199685 0.0223154 -0.417517 +VERTEX3 1691 64.1655 -2.02053 -59.4679 0.0183074 0.013186 -0.385781 +VERTEX3 1692 65.9882 0.571519 -59.7117 0.0574075 0.0131322 -0.379798 +VERTEX3 1693 67.8846 4.15251 -59.721 0.0679322 -0.0211506 -0.350074 +VERTEX3 1694 69.17 8.1552 -59.5264 0.0645466 -0.0612314 -0.322138 +VERTEX3 1695 70.4126 11.3167 -59.367 0.03808 -0.0706774 -0.3118 +VERTEX3 1696 71.7179 15.8947 -59.4617 0.0193038 -0.082456 -0.296601 +VERTEX3 1697 73.0909 20.4201 -60.0504 0.00563424 -0.0499294 -0.253718 +VERTEX3 1698 73.9058 25.0039 -60.3814 0.0206197 -0.0258846 -0.229111 +VERTEX3 1699 74.4806 29.7009 -60.6755 0.0546062 -0.0182068 -0.165146 +VERTEX3 1700 74.3544 34.6867 -60.4748 0.0695779 -0.0216751 -0.129602 +VERTEX3 1701 74.1802 39.677 -60.5095 0.0612297 -0.0298644 -0.0636002 +VERTEX3 1702 73.582 44.5993 -60.6159 0.0348727 -0.00922697 -0.0169943 +VERTEX3 1703 72.614 49.6817 -60.5548 0.0326741 -0.0109325 0.0449876 +VERTEX3 1704 71.2743 54.487 -60.4037 0.0425928 0.00407588 0.0949632 +VERTEX3 1705 69.729 59.4041 -60.0839 0.0495943 0.00595392 0.140326 +VERTEX3 1706 68.0248 63.7815 -59.7291 0.0462903 -0.0023227 0.171427 +VERTEX3 1707 66.3155 68.0637 -59.3526 0.0513778 -0.00647078 0.220588 +VERTEX3 1708 64.5436 72.846 -59.1296 0.0485154 -0.0229759 0.259367 +VERTEX3 1709 62.8404 77.4145 -59.372 0.0275584 -0.0390415 0.301677 +VERTEX3 1710 60.4797 81.3068 -59.4507 0.0202033 -0.0441482 0.338725 +VERTEX3 1711 59.0767 84.7917 -60.3184 -0.0118212 -0.0590962 0.368415 +VERTEX3 1712 56.4974 87.0296 -61.611 -0.0494985 -0.0472883 0.417511 +VERTEX3 1713 55.2505 90.2049 -61.9827 -0.0570955 -0.0359827 0.433114 +VERTEX3 1714 53.3019 91.855 -62.7044 -0.0705535 -0.0204712 0.442438 +VERTEX3 1715 50.872 94.3255 -63.0162 -0.0668881 -0.000329256 0.474599 +VERTEX3 1716 49.1936 94.9755 -62.8802 -0.0724593 0.0298077 0.475115 +VERTEX3 1717 49.1341 98.0803 -63.9714 -0.0677492 0.0376015 0.486526 +VERTEX3 1718 46.8521 98.1144 -62.9838 -0.0394825 0.0523739 0.508271 +VERTEX3 1719 45.2256 99.4973 -61.5657 -0.00437631 0.0604651 0.490813 +VERTEX3 1720 45.2052 96.3534 -60.5041 0.0314596 0.0565641 0.49013 +VERTEX3 1721 44.0464 96.3823 -59.9069 0.0525823 0.0217661 0.514213 +VERTEX3 1722 44.0832 93.9915 -59.0027 -0.00857415 0.0571628 0.434494 +VERTEX3 1723 44.2085 93.2944 -58.0396 0.0650397 0.0501997 0.467071 +VERTEX3 1724 46.5806 89.0765 -57.4312 0.0666503 -0.0946212 0.454995 +VERTEX3 1725 47.6973 86.7758 -57.7257 0.0863492 -0.112585 0.513884 +VERTEX3 1726 48.6564 83.2187 -58.0643 0.177261 -0.107197 0.539185 +VERTEX3 1727 50.0614 73.669 -60.4271 0.0859508 -0.0351274 0.487024 +VERTEX3 1728 50.1269 72.1378 -59.5519 0.0968304 -0.0572411 0.505991 +VERTEX3 1729 51.6289 64.0647 -60.463 0.0676479 -0.021952 0.429308 +VERTEX3 1730 55.7835 49.7732 -60.7178 0.0486592 -0.0535784 0.298203 +VERTEX3 1731 57.1488 44.4036 -61.0898 0.0459442 -0.0533531 0.245034 +VERTEX3 1732 56.1718 28.4248 -61.3515 0.00824817 -0.0231386 0.140473 +VERTEX3 1733 55.0352 14.5195 -61.1758 0.0261326 -0.00919164 0.0750305 +VERTEX3 1734 56.3231 -6.15129 -62.0977 0.00700058 -0.020237 -0.124144 +VERTEX3 1735 51.9878 -10.4694 -60.1149 0.0112769 0.0235055 -0.377364 +VERTEX3 1736 53.1939 -17.7295 -62.4339 -0.0413673 -0.0263325 -0.145663 +VERTEX3 1737 53.5765 -13.8955 -62.1326 -0.0392027 0.013498 -0.115993 +VERTEX3 1738 54.9279 -10.1014 -62.4959 -0.0101166 -0.0253715 -0.297327 +VERTEX3 1739 56.1604 -6.23388 -62.9787 0.0529321 -0.0123385 -0.415158 +VERTEX3 1740 57.8814 -3.80254 -63.2752 0.0109233 0.00542434 -0.359942 +VERTEX3 1741 59.3854 -0.742067 -63.5429 0.0341985 -0.000609707 -0.380215 +VERTEX3 1742 61.3853 2.36111 -63.8216 0.0370305 -0.0168322 -0.373882 +VERTEX3 1743 62.7056 5.78665 -63.6994 0.0697464 -0.0363465 -0.35187 +VERTEX3 1744 64.225 9.4645 -63.5484 0.0594516 -0.0637584 -0.341395 +VERTEX3 1745 65.6247 13.3325 -63.6098 0.03658 -0.0759437 -0.337625 +VERTEX3 1746 67.241 17.3927 -64.0821 0.00458227 -0.061329 -0.297101 +VERTEX3 1747 68.4089 21.7944 -64.4046 0.0158904 -0.0354714 -0.265285 +VERTEX3 1748 69.1995 26.1429 -64.9054 0.0309512 -0.0179822 -0.20953 +VERTEX3 1749 69.5336 30.6739 -64.7877 0.0527196 -0.0191025 -0.16852 +VERTEX3 1750 69.5192 35.3917 -64.7375 0.0607308 -0.0149992 -0.131989 +VERTEX3 1751 69.3292 40.2618 -64.7384 0.0630347 -0.0227009 -0.0517246 +VERTEX3 1752 68.7312 45.035 -64.7933 0.0436394 -0.023063 -0.00355308 +VERTEX3 1753 67.7834 49.5741 -64.8783 0.0490539 -0.0103742 0.0405948 +VERTEX3 1754 66.6094 54.5226 -64.6531 0.041045 -0.0102153 0.0916795 +VERTEX3 1755 64.947 58.9841 -64.3624 0.0500934 -0.00137193 0.135035 +VERTEX3 1756 63.4801 63.4754 -64.0145 0.065226 0.00360539 0.173906 +VERTEX3 1757 61.622 67.7608 -63.504 0.0618711 -0.0109055 0.219572 +VERTEX3 1758 59.7812 72.1596 -63.1062 0.0596254 -0.0169868 0.260357 +VERTEX3 1759 58.1155 76.4019 -63.0846 0.0519292 -0.0310219 0.287382 +VERTEX3 1760 56.3482 80.2468 -63.3294 0.0279986 -0.0468454 0.329745 +VERTEX3 1761 54.0874 83.7585 -63.5919 0.0156552 -0.0470901 0.365466 +VERTEX3 1762 52.6443 86.8863 -64.4157 -0.0151945 -0.0661246 0.392556 +VERTEX3 1763 50.227 88.6119 -65.822 -0.0552322 -0.0545042 0.441882 +VERTEX3 1764 48.4204 91.318 -66.2535 -0.0662409 -0.0333662 0.452266 +VERTEX3 1765 47.2943 93.2038 -67.1005 -0.0766437 -0.0165476 0.465405 +VERTEX3 1766 45.2065 95.3992 -67.2946 -0.0725798 -0.00319633 0.499141 +VERTEX3 1767 43.3668 96.0438 -67.2382 -0.0760618 0.0359872 0.501137 +VERTEX3 1768 44.0228 95.7522 -68.0259 -0.0672127 0.0372323 0.506925 +VERTEX3 1769 40.7409 97.6482 -67.3086 -0.0428731 0.0587607 0.541086 +VERTEX3 1770 39.5602 98.5713 -65.6199 0.00821531 0.0562472 0.510485 +VERTEX3 1771 39.3459 97.2482 -64.1908 0.0286841 0.0452622 0.50917 +VERTEX3 1772 38.0209 97.3059 -63.787 0.0535012 0.0142373 0.536149 +VERTEX3 1773 37.327 96.8171 -62.3239 -0.00443934 0.039068 0.463619 +VERTEX3 1774 39.027 93.92 -61.8194 -0.0101629 -0.0493274 0.450683 +VERTEX3 1775 41.5106 89.9954 -61.8382 0.056301 -0.0562955 0.479161 +VERTEX3 1776 40.2566 88.3126 -62.3392 0.166285 -0.0773232 0.543564 +VERTEX3 1777 41.983 85.6626 -62.1681 0.169947 -0.0850316 0.580736 +VERTEX3 1778 44.7225 74.277 -64.6675 0.0906845 -0.0431956 0.506504 +VERTEX3 1779 44.2997 74.0466 -63.5018 0.101092 -0.0481866 0.517885 +VERTEX3 1780 45.806 66.0834 -64.4375 0.0667343 -0.0262342 0.426623 +VERTEX3 1781 49.7376 57.9573 -64.9033 0.0552413 -0.0492267 0.329298 +VERTEX3 1782 51.7127 49.4154 -65.2496 0.0477929 -0.0567764 0.260465 +VERTEX3 1783 51.8042 33.1071 -65.5734 -0.00670684 -0.029926 0.129556 +VERTEX3 1784 51.0716 18.3023 -65.5085 0.0191902 -0.0183824 0.0633567 +VERTEX3 1785 54.3381 -1.6193 -66.4933 -0.0154732 -0.0316991 -0.15604 +VERTEX3 1786 51.3867 -4.67073 -63.8092 -0.000973995 -0.00225807 -0.424776 +VERTEX3 1787 50.6989 -14.3172 -66.4872 -0.043013 -0.0311849 -0.178406 +VERTEX3 1788 51.1781 -9.25357 -66.7917 -0.0515382 -0.0544333 -0.102505 +VERTEX3 1789 52.2911 -4.95729 -67.2625 0.0418156 -0.0502509 -0.291184 +VERTEX3 1790 53.4023 -1.95538 -67.0019 0.036898 -0.0348244 -0.349426 +VERTEX3 1791 54.7408 0.901373 -67.4448 0.0149885 -0.0341862 -0.312568 +VERTEX3 1792 56.2331 4.45426 -67.5893 0.0481461 -0.0363228 -0.337825 +VERTEX3 1793 57.7984 7.75013 -67.4032 0.0547966 -0.0511088 -0.356205 +VERTEX3 1794 59.1455 10.935 -67.5384 0.0362486 -0.0603257 -0.381828 +VERTEX3 1795 60.9295 14.7174 -67.891 0.00681238 -0.0640295 -0.330537 +VERTEX3 1796 62.1987 18.6796 -68.2441 0.0112598 -0.0450772 -0.317694 +VERTEX3 1797 63.4894 22.9438 -68.7776 0.0194881 -0.0209386 -0.240184 +VERTEX3 1798 63.9877 27.0244 -68.7544 0.0360027 -0.0211803 -0.215373 +VERTEX3 1799 64.2585 31.4965 -68.642 0.0558066 -0.0207846 -0.175224 +VERTEX3 1800 64.284 36.0283 -68.742 0.0656547 -0.014923 -0.12538 +VERTEX3 1801 64.1113 40.8596 -68.6553 0.0586827 -0.0204628 -0.0485757 +VERTEX3 1802 63.5302 45.368 -68.7607 0.0497088 -0.0245773 0.00613674 +VERTEX3 1803 62.5167 49.5883 -68.828 0.0437082 -0.0238253 0.0312588 +VERTEX3 1804 61.4377 54.1962 -68.7682 0.0455089 -0.0126029 0.0908543 +VERTEX3 1805 59.996 58.2482 -68.5501 0.0606525 -0.0167948 0.116544 +VERTEX3 1806 58.3256 62.7179 -68.0633 0.0564886 -0.00177205 0.166854 +VERTEX3 1807 56.7052 66.6598 -67.656 0.0755828 -0.00474091 0.211025 +VERTEX3 1808 54.8557 70.7593 -67.1635 0.0622474 -0.0195536 0.244935 +VERTEX3 1809 52.8983 74.8078 -66.7585 0.0626893 -0.0235536 0.285765 +VERTEX3 1810 51.4424 78.5235 -66.8405 0.0512875 -0.0403206 0.310947 +VERTEX3 1811 49.6889 81.8999 -67.1202 0.0268959 -0.05484 0.351622 +VERTEX3 1812 47.443 85.8119 -67.2704 0.0221461 -0.0604285 0.39053 +VERTEX3 1813 45.8901 89.3066 -68.2615 -0.00797281 -0.0848569 0.421078 +VERTEX3 1814 43.5629 90.9868 -69.7625 -0.0559375 -0.07341 0.477212 +VERTEX3 1815 42.5049 92.4395 -70.2434 -0.0725885 -0.0334114 0.475339 +VERTEX3 1816 40.7608 93.4302 -70.8474 -0.0813349 -0.0201963 0.486377 +VERTEX3 1817 38.974 96.2755 -71.2598 -0.0814795 0.00332032 0.527831 +VERTEX3 1818 36.8964 96.2633 -71.0307 -0.0816237 0.0358263 0.521635 +VERTEX3 1819 37.7773 97.8696 -71.9973 -0.0723257 0.0381067 0.528168 +VERTEX3 1820 35.041 97.5935 -70.9601 -0.0467862 0.0654745 0.565597 +VERTEX3 1821 33.8753 98.6852 -68.8135 0.00349001 0.0452419 0.513332 +VERTEX3 1822 32.5438 98.7539 -67.708 0.0274727 0.0341363 0.528814 +VERTEX3 1823 32.8552 95.5365 -67.3983 0.0339578 0.00323584 0.563058 +VERTEX3 1824 30.6042 96.4327 -65.6226 0.00858175 0.0241303 0.506985 +VERTEX3 1825 31.7509 93.4162 -65.9379 0.105106 0.00313648 0.522596 +VERTEX3 1826 31.7071 97.146 -65.0775 0.143118 -0.0262367 0.573344 +VERTEX3 1827 33.6423 91.5445 -65.4195 0.15523 -0.0442244 0.575294 +VERTEX3 1828 35.8834 87.5045 -65.728 0.178017 -0.0761437 0.603038 +VERTEX3 1829 38.5068 75.0073 -68.0089 0.0777038 -0.039091 0.502337 +VERTEX3 1830 37.741 76.6648 -67.1657 0.0928064 -0.049841 0.522125 +VERTEX3 1831 39.5738 68.1288 -68.3151 0.0688702 -0.0218267 0.432477 +VERTEX3 1832 43.229 61.407 -68.6788 0.049872 -0.0604497 0.354298 +VERTEX3 1833 46.1796 53.7503 -69.2358 0.0404848 -0.0424343 0.272829 +VERTEX3 1834 47.2952 35.8957 -69.7182 0.00511198 -0.030671 0.14576 +VERTEX3 1835 46.3887 23.4366 -69.6325 0.0250362 -0.0240461 0.0450621 +VERTEX3 1836 50.8001 4.37894 -70.7724 -0.0042091 -0.0577055 -0.141137 +VERTEX3 1837 49.5829 2.37075 -67.9502 0.0101198 -0.0531911 -0.400042 +VERTEX3 1838 47.7807 -7.7209 -71.0821 0.0193553 -0.065219 -0.091507 +VERTEX3 1839 48.0417 -4.06701 -70.6586 0.0249012 -0.0767101 -0.0676939 +VERTEX3 1840 48.6204 -0.52556 -70.8098 0.0702206 -0.0385074 -0.176341 +VERTEX3 1841 49.715 2.64014 -71.0752 0.088025 -0.0407426 -0.305623 +VERTEX3 1842 50.9345 5.71366 -70.8407 0.0339793 -0.0714089 -0.311277 +VERTEX3 1843 52.2358 9.06175 -71.0874 0.0306347 -0.0540231 -0.392307 +VERTEX3 1844 54.1976 12.5481 -71.4713 -0.00215719 -0.0551932 -0.343393 +VERTEX3 1845 55.7076 16.1955 -71.781 0.016451 -0.0389927 -0.360111 +VERTEX3 1846 57.1102 19.9438 -72.3465 -0.00373607 -0.0252085 -0.273815 +VERTEX3 1847 58.0361 23.8816 -72.3009 0.0348639 -0.0277618 -0.245947 +VERTEX3 1848 58.5113 28.1356 -72.3239 0.0643751 -0.0291716 -0.202744 +VERTEX3 1849 58.7448 32.3545 -72.378 0.0685432 -0.0120197 -0.156888 +VERTEX3 1850 58.736 36.7586 -72.4224 0.0644997 -0.0077458 -0.121726 +VERTEX3 1851 58.4947 41.2016 -72.3195 0.0611276 -0.00830416 -0.0517221 +VERTEX3 1852 57.8882 45.6027 -72.4269 0.0531953 -0.019875 0.00483553 +VERTEX3 1853 57.0035 49.6977 -72.4611 0.0494983 -0.0255059 0.0437728 +VERTEX3 1854 55.869 53.7867 -72.5259 0.0455818 -0.0175008 0.0799205 +VERTEX3 1855 54.6363 57.7992 -72.4284 0.0477718 -0.0167576 0.116146 +VERTEX3 1856 53.1481 61.8398 -72.0907 0.0649986 -0.0112799 0.166503 +VERTEX3 1857 51.3289 66.0776 -71.4378 0.0603905 -0.00371299 0.225762 +VERTEX3 1858 49.6799 69.4452 -71.0535 0.078099 -0.0131861 0.234482 +VERTEX3 1859 47.9704 73.6655 -70.5783 0.0690108 -0.0302555 0.284582 +VERTEX3 1860 46.0527 77.9255 -70.071 0.0679916 -0.0351452 0.32829 +VERTEX3 1861 44.6581 80.9195 -70.2296 0.0543901 -0.0476633 0.3406 +VERTEX3 1862 42.9964 83.4074 -70.7718 0.0276533 -0.0631747 0.374188 +VERTEX3 1863 40.9327 87.1329 -70.9689 0.0238402 -0.0698928 0.414431 +VERTEX3 1864 39.7237 90.0243 -71.925 -0.0171285 -0.0816139 0.429347 +VERTEX3 1865 36.9445 91.867 -73.2886 -0.0575774 -0.087189 0.503982 +VERTEX3 1866 35.6847 94.0752 -73.9 -0.0814237 -0.0493982 0.504019 +VERTEX3 1867 34.0506 93.6469 -74.7703 -0.0908416 -0.0276637 0.514528 +VERTEX3 1868 32.4114 95.8517 -74.4978 -0.0918378 -0.00377598 0.543957 +VERTEX3 1869 30.5043 95.8527 -74.231 -0.0874893 0.0317217 0.530791 +VERTEX3 1870 31.4973 97.6436 -75.4362 -0.0708186 0.031852 0.547094 +VERTEX3 1871 28.3763 97.7909 -74.0527 -0.0497846 0.0730399 0.593917 +VERTEX3 1872 27.9061 99.5666 -72.2657 -0.00870408 0.0377193 0.509776 +VERTEX3 1873 27.3665 98.0906 -71.2106 0.0121083 0.0161978 0.519718 +VERTEX3 1874 26.3572 96.7325 -70.7668 -0.0455768 0.00657163 0.498587 +VERTEX3 1875 25.5615 94.839 -69.2198 0.0371563 0.0200439 0.541686 +VERTEX3 1876 24.986 94.3408 -68.7426 0.119811 -0.00826249 0.641577 +VERTEX3 1877 25.9407 92.8078 -68.5984 0.108256 -0.00568681 0.628982 +VERTEX3 1878 26.6432 92.4314 -68.7597 0.140817 -0.0299348 0.610857 +VERTEX3 1879 27.7448 91.6545 -68.0164 0.156039 -0.0848344 0.610157 +VERTEX3 1880 31.0623 78.0268 -71.4907 0.0693311 -0.0316486 0.526857 +VERTEX3 1881 31.9342 76.4005 -70.5516 0.0902305 -0.0488824 0.530424 +VERTEX3 1882 33.2064 70.5789 -71.3644 0.0559091 -0.01573 0.434626 +VERTEX3 1883 38.4751 62.1267 -72.6886 0.0523241 -0.0533454 0.36118 +VERTEX3 1884 41.7628 54.5776 -73.0264 0.0482672 -0.0575338 0.23991 +VERTEX3 1885 42.5451 38.8532 -73.327 0.00965469 -0.0382898 0.145106 +VERTEX3 1886 42.7198 31.3109 -73.2648 0.0403775 -0.0394006 0.0904425 +VERTEX3 1887 47.7873 10.4648 -74.7441 0.0101594 -0.0660065 -0.0895705 +VERTEX3 1888 48.9082 8.07421 -71.6188 0.0530299 -0.122187 -0.390501 +VERTEX3 1889 44.3558 -3.12046 -74.0271 0.0427791 -0.0675318 -0.00520117 +VERTEX3 1890 44.2658 0.146922 -74.4368 0.0265395 -0.0311434 0.0224595 +VERTEX3 1891 44.4759 4.08223 -74.0772 0.0319812 -0.0259037 -0.145474 +VERTEX3 1892 45.6906 7.56433 -74.2783 0.0298423 -0.0383224 -0.358355 +VERTEX3 1893 47.4883 10.7377 -74.6742 -0.000653894 -0.0351765 -0.289304 +VERTEX3 1894 48.9165 14.2972 -75.1012 0.0284853 -0.0240271 -0.356378 +VERTEX3 1895 50.4273 17.5658 -75.4973 -0.00548515 -0.025442 -0.276841 +VERTEX3 1896 51.5801 21.0719 -75.5771 0.0433387 -0.0334902 -0.276346 +VERTEX3 1897 52.407 25.1091 -75.6664 0.0827169 -0.0387254 -0.212105 +VERTEX3 1898 52.8462 29.0943 -75.7821 0.0661201 -0.00890314 -0.178046 +VERTEX3 1899 53.0241 33.2373 -75.8292 0.0731518 0.00944145 -0.14312 +VERTEX3 1900 52.9784 37.4437 -75.8124 0.0545659 0.0107846 -0.0985955 +VERTEX3 1901 52.6765 41.6955 -75.6776 0.0567996 -0.000144775 -0.043312 +VERTEX3 1902 52.1132 45.8058 -75.6419 0.0569245 -0.00992546 0.00420332 +VERTEX3 1903 51.2782 49.7469 -75.7522 0.0446038 -0.0195664 0.0425253 +VERTEX3 1904 50.223 53.6573 -75.9056 0.0474965 -0.0159187 0.0979833 +VERTEX3 1905 48.9467 57.4311 -75.7609 0.048903 -0.00889394 0.129918 +VERTEX3 1906 47.6644 60.9757 -75.7237 0.0566702 -0.0136726 0.16626 +VERTEX3 1907 45.9323 64.8232 -75.1949 0.0644641 -0.0158518 0.216885 +VERTEX3 1908 44.0439 68.6311 -74.5221 0.0660979 -0.0114449 0.264715 +VERTEX3 1909 42.4649 72.0947 -74.1379 0.07747 -0.0177242 0.279348 +VERTEX3 1910 40.9603 75.6996 -73.8419 0.0749661 -0.0298082 0.316323 +VERTEX3 1911 38.836 79.2882 -73.1883 0.0676941 -0.0415307 0.343729 +VERTEX3 1912 37.4306 82.5704 -73.4097 0.0650714 -0.0619873 0.382384 +VERTEX3 1913 36.1086 85.1943 -73.9748 0.0324046 -0.0732406 0.400791 +VERTEX3 1914 34.3165 88.4465 -74.1554 0.0170483 -0.079472 0.437677 +VERTEX3 1915 33.2356 89.4338 -75.4171 -0.0303389 -0.0750736 0.429464 +VERTEX3 1916 30.7357 90.7804 -76.8708 -0.0753643 -0.0709983 0.495239 +VERTEX3 1917 29.3697 93.8517 -77.2655 -0.0847643 -0.0553499 0.518952 +VERTEX3 1918 27.9607 93.3514 -78.2418 -0.09505 -0.0356567 0.528513 +VERTEX3 1919 26.6967 95.5142 -78.3213 -0.0937122 -0.0231254 0.561295 +VERTEX3 1920 24.0903 96.1564 -77.3042 -0.0873097 0.0300479 0.556854 +VERTEX3 1921 25.502 96.2981 -78.496 -0.0707939 0.0135777 0.54991 +VERTEX3 1922 21.6296 97.8238 -76.9635 -0.051452 0.0771031 0.629486 +VERTEX3 1923 21.479 98.8785 -75.0754 -0.0412234 0.00415065 0.504323 +VERTEX3 1924 21.4452 96.9748 -74.6804 -0.113834 0.0167937 0.486479 +VERTEX3 1925 19.4613 97.5269 -73.5974 -0.0578181 0.0177974 0.584887 +VERTEX3 1926 16.9293 96.9671 -71.9714 0.0485484 0.0214901 0.665904 +VERTEX3 1927 19.3062 93.5457 -71.5992 0.02296 0.0425284 0.61955 +VERTEX3 1928 19.443 91.5848 -71.4124 0.0898132 0.00939128 0.636407 +VERTEX3 1929 19.1323 94.9609 -71.1906 0.12309 -0.0206251 0.632929 +VERTEX3 1930 22.0107 90.9892 -71.0253 0.138306 -0.0742575 0.621506 +VERTEX3 1931 24.3411 77.9382 -74.1613 0.0610564 -0.0214447 0.537952 +VERTEX3 1932 24.9718 77.839 -73.4342 0.079377 -0.0562397 0.559959 +VERTEX3 1933 26.5457 74.3197 -74.1058 0.0655314 -0.0104352 0.479969 +VERTEX3 1934 33.0352 65.6626 -75.727 0.0632631 -0.0434166 0.378416 +VERTEX3 1935 36.8998 50.5081 -76.7578 0.0449163 -0.0630733 0.23286 +VERTEX3 1936 35.7465 43.1918 -76.66 0.0305953 -0.0384996 0.156694 +VERTEX3 1937 36.7778 35.3007 -76.5388 0.0530877 -0.0438974 0.128123 +VERTEX3 1938 44.97 15.6653 -78.5937 0.03539 -0.0664452 -0.0380426 +VERTEX3 1939 45.2239 14.004 -75.3575 0.0604397 -0.0956521 -0.201077 +VERTEX3 1940 39.3976 0.762585 -76.4525 0.0748007 0.00627836 0.11115 +VERTEX3 1941 39.9846 4.63833 -77.2016 0.0873847 0.0174208 0.290373 +VERTEX3 1942 40.6842 8.34019 -77.5525 0.0686212 0.033083 -0.0851293 +VERTEX3 1943 41.9796 12.0302 -77.9001 0.0590025 0.0140724 -0.305938 +VERTEX3 1944 43.5776 15.2548 -78.2923 0.0159239 -0.00777515 -0.244819 +VERTEX3 1945 44.8587 18.6454 -78.5065 0.060029 -0.0389079 -0.280305 +VERTEX3 1946 45.9511 22.3728 -78.7411 0.0931855 -0.0334258 -0.203146 +VERTEX3 1947 46.5877 26.0756 -78.8032 0.0694916 -0.00456786 -0.204156 +VERTEX3 1948 46.9556 30.0297 -78.949 0.0828498 0.0186215 -0.147817 +VERTEX3 1949 47.1571 34.074 -78.8654 0.0562827 0.0190139 -0.123599 +VERTEX3 1950 46.9524 38.1018 -78.7208 0.0608436 0.00622471 -0.0816126 +VERTEX3 1951 46.6736 42.1107 -78.6566 0.0575091 -0.000774509 -0.0349605 +VERTEX3 1952 46.0745 45.9823 -78.5978 0.0584532 -0.00780566 0.00991831 +VERTEX3 1953 45.2493 49.7224 -78.6616 0.050468 -0.0157779 0.0514239 +VERTEX3 1954 44.2446 53.3852 -78.8086 0.0365802 -0.0188592 0.0891382 +VERTEX3 1955 43.0869 56.932 -78.8784 0.0436227 -0.00608156 0.131368 +VERTEX3 1956 41.6857 60.2748 -78.7072 0.063056 -0.0145801 0.149291 +VERTEX3 1957 40.3485 63.7729 -78.5516 0.047502 -0.0227672 0.190381 +VERTEX3 1958 38.5869 67.1383 -78.0453 0.0709781 -0.0116698 0.253595 +VERTEX3 1959 36.7861 70.5664 -77.4552 0.0769042 -0.011282 0.279885 +VERTEX3 1960 35.0385 74.1188 -76.9573 0.0885218 -0.0224047 0.333323 +VERTEX3 1961 33.6776 77.4263 -76.7163 0.0712455 -0.0337445 0.353242 +VERTEX3 1962 31.633 80.176 -76.1822 0.0767151 -0.0440396 0.371115 +VERTEX3 1963 30.1055 83.172 -76.2283 0.0571075 -0.0697134 0.399278 +VERTEX3 1964 28.8474 85.4199 -76.9736 0.0327172 -0.0794347 0.414074 +VERTEX3 1965 26.9911 88.4253 -77.215 0.015787 -0.0880039 0.457925 +VERTEX3 1966 26.1023 89.7187 -78.334 -0.0179878 -0.0883208 0.455279 +VERTEX3 1967 23.7294 90.3741 -80.1275 -0.0732659 -0.088739 0.525754 +VERTEX3 1968 22.808 92.2368 -80.4656 -0.0843487 -0.0574289 0.533569 +VERTEX3 1969 22.0488 92.5593 -81.1812 -0.0907704 -0.0392747 0.536926 +VERTEX3 1970 20.0246 95.3647 -81.1615 -0.0981018 -0.0446423 0.574279 +VERTEX3 1971 18.2861 93.9276 -79.8236 -0.0898721 0.0215666 0.563819 +VERTEX3 1972 19.3691 95.5119 -81.3306 -0.0743501 0.000850648 0.550503 +VERTEX3 1973 15.2219 96.6198 -79.347 -0.0691886 0.046616 0.638201 +VERTEX3 1974 14.5841 99.3252 -78.4554 -0.130245 -0.010459 0.532067 +VERTEX3 1975 14.5622 96.4233 -77.8165 -0.114993 0.0170842 0.551151 +VERTEX3 1976 10.0471 99.1918 -75.9075 -0.0371201 0.0169997 0.669441 +VERTEX3 1977 9.25447 97.6024 -74.0004 -0.0150127 0.0454837 0.63089 +VERTEX3 1978 11.5359 93.8944 -74.4977 0.0299729 0.0712649 0.642413 +VERTEX3 1979 11.8613 93.4285 -73.7741 0.0726103 0.0159853 0.647898 +VERTEX3 1980 12.9441 94.6217 -73.6212 0.102954 -0.0214397 0.630423 +VERTEX3 1981 15.9283 87.4026 -74.4691 0.129178 -0.0548504 0.622895 +VERTEX3 1982 18.0204 82.1859 -76.4879 0.0436971 -0.0220331 0.553682 +VERTEX3 1983 17.6849 80.2446 -75.8019 0.0868338 -0.0317355 0.570846 +VERTEX3 1984 19.9782 75.0866 -76.6981 0.067256 -0.00295401 0.499612 +VERTEX3 1985 26.397 67.8193 -78.5629 0.0635666 -0.0419446 0.397068 +VERTEX3 1986 30.8282 54.9442 -79.4295 0.0513358 -0.0539242 0.235964 +VERTEX3 1987 30.6369 48.4292 -79.5573 0.0612329 -0.0229929 0.181574 +VERTEX3 1988 34.1711 39.3641 -79.4145 0.0690593 -0.0512033 0.165084 +VERTEX3 1989 40.5253 20.4014 -81.4225 0.0410996 -0.0571432 0.0291694 +VERTEX3 1990 41.1713 19.138 -78.1516 0.0973976 -0.0660403 0.0694834 +VERTEX3 1991 35.4576 4.68454 -79.9672 0.141007 0.00760599 0.154831 +VERTEX3 1992 35.4919 8.49002 -80.3714 0.0943516 0.0344841 0.282268 +VERTEX3 1993 36.4435 12.9171 -80.8009 0.0856261 0.0194345 -0.0881992 +VERTEX3 1994 37.933 16.0737 -81.098 0.0577474 -0.0178556 -0.241333 +VERTEX3 1995 39.2535 19.8117 -81.3975 0.0983559 -0.0244375 -0.16547 +VERTEX3 1996 40.047 23.4044 -81.4756 0.0755447 0.00835773 -0.236466 +VERTEX3 1997 40.6849 27.0933 -81.643 0.09713 0.0298163 -0.14202 +VERTEX3 1998 40.9833 30.8942 -81.578 0.0648936 0.0287971 -0.141801 +VERTEX3 1999 40.9878 34.7622 -81.482 0.0532878 0.00746004 -0.0931129 +VERTEX3 2000 40.7599 38.5881 -81.3918 0.0626097 -0.00178757 -0.0626329 +VERTEX3 2001 40.4356 42.431 -81.2878 0.0555154 -0.00506915 -0.0248232 +VERTEX3 2002 39.9148 46.14 -81.2412 0.0527279 -0.00339003 0.0242243 +VERTEX3 2003 39.1123 49.7141 -81.282 0.0559819 -0.012948 0.0546299 +VERTEX3 2004 38.086 53.2033 -81.3388 0.0389824 -0.0152592 0.0873154 +VERTEX3 2005 37.0126 56.4561 -81.4356 0.0417022 -0.0117098 0.126044 +VERTEX3 2006 35.7006 59.6377 -81.4676 0.0489646 -0.00837448 0.157983 +VERTEX3 2007 34.2124 62.7424 -81.2941 0.0588396 -0.00912422 0.193952 +VERTEX3 2008 32.8572 65.9552 -81.1679 0.0614528 -0.0232299 0.231523 +VERTEX3 2009 31.1397 69.2136 -80.5595 0.0719747 -0.0154259 0.268935 +VERTEX3 2010 29.4314 71.8531 -80.0309 0.0786852 -0.0126794 0.297042 +VERTEX3 2011 27.8506 75.3425 -79.4987 0.0884411 -0.0281845 0.336231 +VERTEX3 2012 26.3386 77.9337 -79.2548 0.0804978 -0.0449886 0.339081 +VERTEX3 2013 24.23 80.9224 -78.8128 0.0857474 -0.0549773 0.413886 +VERTEX3 2014 22.8595 83.7054 -78.9023 0.0702921 -0.0849524 0.437234 +VERTEX3 2015 21.6956 86.6764 -79.5909 0.0385249 -0.0982523 0.456638 +VERTEX3 2016 19.9678 88.2306 -80.0323 0.024132 -0.104128 0.478787 +VERTEX3 2017 19.1976 89.3763 -81.3932 -0.0205904 -0.0981521 0.487893 +VERTEX3 2018 17.1105 89.8889 -82.91 -0.0627063 -0.103832 0.559412 +VERTEX3 2019 16.6859 91.3275 -83.2604 -0.0788411 -0.062797 0.549254 +VERTEX3 2020 15.6964 91.5584 -83.9378 -0.0873838 -0.0598267 0.551004 +VERTEX3 2021 14.3648 93.2868 -83.7416 -0.0948045 -0.0655157 0.568999 +VERTEX3 2022 13.3612 91.2222 -82.7605 -0.0926581 0.012078 0.579448 +VERTEX3 2023 13.6466 93.1127 -84.4531 -0.102246 -0.0545069 0.541298 +VERTEX3 2024 11.2325 93.3272 -82.8532 -0.149148 -0.0577159 0.502825 +VERTEX3 2025 9.29993 93.0536 -81.3405 -0.150999 -0.0190247 0.587865 +VERTEX3 2026 6.10611 97.5651 -79.9603 -0.102172 0.0137303 0.612153 +VERTEX3 2027 2.85611 97.4212 -77.9474 -0.0233576 0.010564 0.696969 +VERTEX3 2028 1.7192 97.5443 -76.7102 -0.0124749 0.0637671 0.646009 +VERTEX3 2029 3.8061 96.9095 -76.7039 0.0296187 0.0460259 0.676427 +VERTEX3 2030 4.63129 94.9065 -75.58 0.0721879 0.0042416 0.658464 +VERTEX3 2031 8.243 89.5189 -76.806 0.0909659 -0.0513534 0.612778 +VERTEX3 2032 7.53075 91.0373 -76.2816 0.132098 -0.0674787 0.655215 +VERTEX3 2033 9.96755 81.1449 -79.0855 0.0494774 -0.021918 0.563363 +VERTEX3 2034 11.5755 80.2282 -78.2764 0.0838184 -0.0215837 0.560912 +VERTEX3 2035 13.3695 75.8195 -78.9298 0.0748057 -0.012148 0.515693 +VERTEX3 2036 20.5397 68.5642 -81.2041 0.0720635 -0.0378482 0.394968 +VERTEX3 2037 23.8299 62.4746 -81.8951 0.0635937 -0.018939 0.289286 +VERTEX3 2038 25.2779 53.957 -81.7809 0.0737504 0.000395671 0.219494 +VERTEX3 2039 28.6326 42.3836 -81.4158 0.105169 -0.0406259 0.201124 +VERTEX3 2040 36.9044 25.2454 -83.9854 0.09121 -0.0375593 0.0480131 +VERTEX3 2041 37.1644 23.5931 -80.6249 0.135641 -0.010971 0.00215452 +VERTEX3 2042 30.6109 8.92323 -82.8131 0.178299 0.0308416 0.106919 +VERTEX3 2043 31.3049 12.3188 -83.2945 0.12111 0.110064 0.181783 +VERTEX3 2044 32.4631 16.5499 -83.6093 0.0256117 0.0558443 -0.0902135 +VERTEX3 2045 33.2612 20.5381 -83.8106 0.113115 0.0290952 -0.242531 +VERTEX3 2046 34.1251 24.3878 -83.8784 0.0946885 0.0300854 -0.107271 +VERTEX3 2047 34.6207 28.0037 -83.8381 0.0645083 0.0392504 -0.134196 +VERTEX3 2048 34.7638 31.5823 -83.7246 0.0481873 0.00323533 -0.0944506 +VERTEX3 2049 34.7386 35.1793 -83.8056 0.0532923 -0.00773964 -0.0695123 +VERTEX3 2050 34.5423 39.0126 -83.7789 0.0532896 -0.00427051 -0.0366751 +VERTEX3 2051 34.1816 42.7091 -83.6245 0.0571378 -0.0082795 -0.0100111 +VERTEX3 2052 33.6386 46.2587 -83.5712 0.0537359 -0.00423278 0.0178886 +VERTEX3 2053 32.8068 49.6586 -83.559 0.043355 -0.0127213 0.052519 +VERTEX3 2054 31.8013 52.8707 -83.5585 0.0479291 -0.0177583 0.094279 +VERTEX3 2055 30.6525 56.1081 -83.701 0.0354619 -0.0100209 0.120514 +VERTEX3 2056 29.4706 59.0422 -83.6946 0.034425 -0.00602211 0.163871 +VERTEX3 2057 28.1775 61.8816 -83.6654 0.0446807 0.00223513 0.165387 +VERTEX3 2058 26.5228 64.6581 -83.3603 0.0519731 -0.00802533 0.232559 +VERTEX3 2059 24.948 67.3752 -83.1884 0.0568428 0.00284082 0.286105 +VERTEX3 2060 23.4758 70.3972 -82.6534 0.0696108 -0.00590124 0.302908 +VERTEX3 2061 21.821 72.9392 -82.2477 0.0739015 -0.0159087 0.331775 +VERTEX3 2062 20.2975 75.8178 -81.7778 0.0918027 -0.025868 0.349756 +VERTEX3 2063 18.9159 78.565 -81.6263 0.0706382 -0.0513819 0.393698 +VERTEX3 2064 17.0597 81.0097 -81.3082 0.0871394 -0.0666701 0.432751 +VERTEX3 2065 15.4561 83.8511 -81.3147 0.0791463 -0.0896172 0.464547 +VERTEX3 2066 14.1864 86.0068 -82.157 0.0404523 -0.107971 0.494905 +VERTEX3 2067 12.9651 87.8764 -82.6688 0.030267 -0.116699 0.511912 +VERTEX3 2068 12.3045 88.9928 -84.179 -0.00216064 -0.119486 0.526916 +VERTEX3 2069 10.2528 88.797 -85.2919 -0.0387746 -0.111783 0.602893 +VERTEX3 2070 9.80535 90.9387 -85.4369 -0.0501389 -0.0993777 0.583977 +VERTEX3 2071 9.16036 89.5295 -86.2651 -0.0824807 -0.0777186 0.554661 +VERTEX3 2072 8.61301 90.6894 -85.8006 -0.0644884 -0.0797484 0.556349 +VERTEX3 2073 6.0255 89.956 -85.039 -0.0987078 0.0061534 0.565269 +VERTEX3 2074 7.88408 92.1315 -87.7246 -0.212441 -0.116268 0.507132 +VERTEX3 2075 5.21389 88.9443 -85.723 -0.168566 -0.0532508 0.621515 +VERTEX3 2076 2.69788 91.8289 -84.3502 -0.14482 -0.0368777 0.615906 +VERTEX3 2077 -2.07436 94.1466 -81.7257 -0.0875297 0.00201308 0.663464 +VERTEX3 2078 -4.11861 93.7246 -79.9599 -0.00993509 0.00403457 0.710582 +VERTEX3 2079 -5.33246 97.4421 -78.6965 0.00413603 0.0477431 0.688219 +VERTEX3 2080 -2.71068 92.6864 -78.6001 0.0332008 0.0345172 0.698171 +VERTEX3 2081 -1.76222 91.1676 -78.0498 0.0786855 -0.000137918 0.66347 +VERTEX3 2082 0.0854451 90.5317 -78.8298 0.117325 -0.0451849 0.638551 +VERTEX3 2083 0.716968 87.2533 -79.2609 0.128226 -0.0711413 0.663907 +VERTEX3 2084 3.15642 81.1969 -80.9143 0.0594741 -0.02347 0.594176 +VERTEX3 2085 4.71291 79.5289 -80.8875 0.0946156 -0.0439354 0.617505 +VERTEX3 2086 6.04421 76.8796 -80.7899 0.0780193 -0.00519796 0.528813 +VERTEX3 2087 13.2752 70.2637 -83.1182 0.0785033 -0.0343548 0.414009 +VERTEX3 2088 16.205 66.8186 -83.4462 0.0803667 -0.00809935 0.321697 +VERTEX3 2089 20.3243 56.6614 -83.4107 0.0859119 0.0103291 0.23649 +VERTEX3 2090 22.6071 46.9737 -83.0334 0.124417 -0.0163069 0.240139 +VERTEX3 2091 30.9614 29.1471 -86.056 0.0982134 -0.0119317 0.0630405 +VERTEX3 2092 32.0326 27.9634 -83.1447 0.169571 0.0224512 -0.0341313 +VERTEX3 2093 26.37 12.2234 -84.8527 0.0395428 0.0811368 0.0737493 +VERTEX3 2094 26.835 16.9482 -85.4993 -0.0069056 0.047071 0.176479 +VERTEX3 2095 27.6244 21.6295 -85.5746 0.0179836 -0.00862691 -0.0454231 +VERTEX3 2096 28.1766 25.0249 -85.6696 0.0718067 0.0263806 -0.117667 +VERTEX3 2097 28.3301 28.3965 -85.6474 0.0433474 -0.00728908 -0.0781235 +VERTEX3 2098 28.5956 31.7989 -85.826 0.0424355 -0.0123338 -0.0503035 +VERTEX3 2099 28.5316 35.3905 -85.8681 0.0478232 -0.00589004 -0.0418625 +VERTEX3 2100 28.2887 39.2638 -85.8645 0.0578278 -0.00803495 -0.0194572 +VERTEX3 2101 27.8813 43.0043 -85.7001 0.0548511 -0.0151308 -0.000820259 +VERTEX3 2102 27.3117 46.4751 -85.5917 0.0508446 -0.00010016 0.0234164 +VERTEX3 2103 26.5017 49.6768 -85.5443 0.0474012 -0.0119646 0.0570464 +VERTEX3 2104 25.5163 52.7468 -85.5624 0.0398394 -0.0185799 0.0850362 +VERTEX3 2105 24.372 55.7045 -85.5801 0.0364677 -0.00875465 0.123829 +VERTEX3 2106 23.1355 58.4267 -85.5616 0.0260707 -0.0143636 0.147497 +VERTEX3 2107 21.8316 61.0204 -85.5301 0.0279862 0.00181258 0.190089 +VERTEX3 2108 20.4831 63.7224 -85.3266 0.0352458 0.00886067 0.20327 +VERTEX3 2109 18.7956 66.1999 -84.9974 0.039773 0.00179714 0.268146 +VERTEX3 2110 17.2246 68.4476 -84.8448 0.0524037 0.00479596 0.31846 +VERTEX3 2111 15.6879 71.1197 -84.3791 0.0705106 0.00378009 0.336909 +VERTEX3 2112 14.1521 73.2974 -84.0705 0.0764135 -0.0175097 0.35302 +VERTEX3 2113 12.5514 75.6335 -83.5801 0.0843354 -0.0407246 0.401118 +VERTEX3 2114 11.225 78.3883 -83.5548 0.0780064 -0.0492917 0.419609 +VERTEX3 2115 10.1262 80.8709 -83.6398 0.0837756 -0.0733875 0.433159 +VERTEX3 2116 8.2499 83.1106 -83.5742 0.0886329 -0.0932051 0.495186 +VERTEX3 2117 6.84383 84.6665 -84.1835 0.0437442 -0.119012 0.513604 +VERTEX3 2118 5.91447 85.5864 -84.9627 0.0337708 -0.113187 0.528265 +VERTEX3 2119 5.49645 87.4518 -86.4388 -0.00165373 -0.122638 0.556498 +VERTEX3 2120 3.49706 86.8458 -87.2716 -0.0281845 -0.118571 0.607441 +VERTEX3 2121 3.04709 88.1668 -87.4858 -0.0388034 -0.0974479 0.594671 +VERTEX3 2122 2.97687 87.9358 -88.2363 -0.0699044 -0.101528 0.555215 +VERTEX3 2123 1.96557 88.3345 -87.4894 -0.0733296 -0.0900134 0.538457 +VERTEX3 2124 1.86959 87.9682 -88.5837 -0.12994 -0.151403 0.466804 +VERTEX3 2125 1.48676 88.3267 -90.0909 -0.203944 -0.106238 0.609845 +VERTEX3 2126 -1.00845 87.7566 -89.3068 -0.18304 -0.157893 0.652104 +VERTEX3 2127 -4.72409 88.6341 -86.7466 -0.12335 -0.0535365 0.653507 +VERTEX3 2128 -9.5428 91.689 -83.0155 -0.0483839 0.00775433 0.703119 +VERTEX3 2129 -11.0832 91.5288 -82.0828 0.0320013 0.00653879 0.779219 +VERTEX3 2130 -12.1738 94.5236 -80.3392 0.0107212 0.049133 0.70939 +VERTEX3 2131 -10.0688 90.196 -80.1196 0.0676094 0.0239131 0.725968 +VERTEX3 2132 -8.92858 90.7979 -79.575 0.0981619 -0.0298122 0.694357 +VERTEX3 2133 -7.72232 89.689 -79.4618 0.128066 -0.0311166 0.655874 +VERTEX3 2134 -7.52264 86.0488 -80.5517 0.1649 -0.0772111 0.706791 +VERTEX3 2135 -2.94821 76.6426 -83.19 0.074619 -0.0188033 0.611991 +VERTEX3 2136 -3.09225 77.5116 -82.5687 0.100208 -0.0496773 0.641992 +VERTEX3 2137 -2.29397 75.4963 -82.2921 0.0801652 -0.0133826 0.557309 +VERTEX3 2138 6.31504 70.3743 -85.0365 0.0550685 -0.0275175 0.445197 +VERTEX3 2139 9.19418 68.1566 -84.5833 0.0757831 0.00745422 0.351282 +VERTEX3 2140 12.1748 59.1231 -84.7792 0.0824904 0.0319236 0.268874 +VERTEX3 2141 17.7249 48.4467 -85.1966 0.11947 -0.00401447 0.250789 +VERTEX3 2142 24.8674 32.288 -86.8169 0.0851689 0.000742898 0.0666717 +VERTEX3 2143 26.7842 32.7526 -84.0394 0.0604382 0.00298747 -0.0972074 +VERTEX3 2144 22.9044 18.258 -86.8396 -0.0119474 -0.0324646 -0.0293011 +VERTEX3 2145 21.946 21.9655 -86.9637 -0.0175105 -0.116215 0.0343457 +VERTEX3 2146 22.1093 25.7389 -87.3067 0.0398916 -0.0185703 -0.0592771 +VERTEX3 2147 22.4825 28.7377 -87.5099 0.0373099 -0.0105938 -0.0514556 +VERTEX3 2148 22.5344 31.8102 -87.5843 0.0480397 -0.0138408 -0.02935 +VERTEX3 2149 22.413 35.1516 -87.6161 0.046826 -0.0142177 0.0102079 +VERTEX3 2150 22.0872 39.3751 -87.5809 0.0370333 -0.00951407 -0.0048061 +VERTEX3 2151 21.5991 43.4046 -87.5808 0.0455734 -0.00403579 0.0105308 +VERTEX3 2152 21.0028 46.8098 -87.3574 0.0484471 -0.00853964 0.0183059 +VERTEX3 2153 20.1841 49.8845 -87.1498 0.0533349 0.00186745 0.0577735 +VERTEX3 2154 19.2668 52.7922 -87.1573 0.0396434 -0.0225669 0.0863421 +VERTEX3 2155 18.158 55.4408 -87.1944 0.0443021 -0.016011 0.122051 +VERTEX3 2156 16.8033 57.9298 -87.1455 0.0338998 -0.0115199 0.156057 +VERTEX3 2157 15.4937 60.2661 -87.0744 0.0144642 -0.012263 0.183393 +VERTEX3 2158 14.2038 62.5685 -86.9083 0.0233847 0.000912242 0.221617 +VERTEX3 2159 12.7262 64.8406 -86.6518 0.0230927 0.0114155 0.26811 +VERTEX3 2160 10.8165 66.5822 -86.2948 0.0293884 0.0100912 0.317748 +VERTEX3 2161 9.36252 69.0291 -86.1012 0.0483477 -0.00160536 0.338498 +VERTEX3 2162 7.87264 71.202 -85.7075 0.0695868 -0.00433769 0.372113 +VERTEX3 2163 6.2556 72.7985 -85.4125 0.0510762 -0.0218987 0.41194 +VERTEX3 2164 4.8946 75.2378 -85.1459 0.0913781 -0.0300965 0.458245 +VERTEX3 2165 3.4504 77.5237 -85.1433 0.0835395 -0.0449172 0.478539 +VERTEX3 2166 2.65616 79.8988 -85.4705 0.092832 -0.0805468 0.458074 +VERTEX3 2167 1.00181 81.7609 -85.1986 0.0742895 -0.105677 0.508851 +VERTEX3 2168 -0.29051 83.0413 -86.1074 0.0573884 -0.132094 0.544662 +VERTEX3 2169 -1.31562 83.9933 -86.6151 0.0376515 -0.120793 0.589598 +VERTEX3 2170 -2.00214 84.9116 -88.4304 0.0190973 -0.112602 0.604581 +VERTEX3 2171 -3.23043 84.4407 -89.0344 -0.0140785 -0.121231 0.610856 +VERTEX3 2172 -3.92153 85.1857 -89.3279 -0.0184642 -0.115705 0.622273 +VERTEX3 2173 -3.77134 85.268 -90.0429 -0.0454441 -0.104908 0.552169 +VERTEX3 2174 -4.65356 85.5777 -89.1687 -0.0559612 -0.0815005 0.50913 +VERTEX3 2175 -4.32665 85.1656 -92.2244 -0.154355 -0.215721 0.521151 +VERTEX3 2176 -4.66212 85.638 -93.1377 -0.23383 -0.143649 0.658356 +VERTEX3 2177 -6.8185 84.2358 -91.3375 -0.14321 -0.10731 0.675582 +VERTEX3 2178 -12.509 87.1407 -88.4816 -0.0886555 -0.00334049 0.712524 +VERTEX3 2179 -16.8509 89.6678 -83.85 0.0148775 0.0319656 0.73975 +VERTEX3 2180 -17.6722 88.447 -83.71 0.025572 0.0148284 0.829327 +VERTEX3 2181 -18.6577 90.2934 -81.4577 0.0305519 0.0569415 0.760543 +VERTEX3 2182 -15.9026 85.7975 -81.133 0.0788247 0.0320382 0.739417 +VERTEX3 2183 -18.0913 89.8247 -79.7858 0.149073 -0.0206896 0.769805 +VERTEX3 2184 -14.9782 87.7241 -81.1194 0.1565 -0.0286867 0.712056 +VERTEX3 2185 -14.0298 81.9858 -82.2944 0.174499 -0.0792735 0.734223 +VERTEX3 2186 -11.163 75.2578 -84.2586 0.0773982 -0.0387776 0.619108 +VERTEX3 2187 -11.2716 76.316 -83.4225 0.0885283 -0.0413106 0.694424 +VERTEX3 2188 -9.31986 74.7234 -83.4242 0.0768401 -0.00804366 0.597363 +VERTEX3 2189 -2.4011 74.5708 -85.917 0.0313288 -0.0212139 0.508444 +VERTEX3 2190 3.39947 67.5464 -85.79 0.0805489 0.013599 0.379546 +VERTEX3 2191 5.70867 60.2679 -85.998 0.0758443 0.038523 0.298099 +VERTEX3 2192 10.991 48.6416 -85.9646 0.103162 -0.00460586 0.247197 +VERTEX3 2193 16.4362 36.0375 -86.6343 0.080482 -0.0285982 0.0620725 +VERTEX3 2194 25.8089 41.3126 -86.129 0.00931581 -0.158237 -0.26874 +VERTEX3 2195 17.4577 25.9681 -88.0948 0.0155294 -0.0112181 -0.0363624 +VERTEX3 2196 16.5712 26.2782 -88.8208 0.0189714 -0.0179318 -0.0367534 +VERTEX3 2197 16.5033 28.8886 -88.9656 0.0287555 -0.0189706 -0.0464295 +VERTEX3 2198 16.5143 31.7149 -88.9742 0.0445089 -0.0106482 -0.0154963 +VERTEX3 2199 16.3609 34.3897 -88.9486 0.0458629 -0.0248266 0.0647399 +EDGE3 0 1 0.142135 2.35517 -0.0102327 -0.0319376 0.0249381 0.144005 +EDGE3 1 2 -0.0302179 2.31152 -0.263451 -0.0324139 -0.000441195 0.148003 +EDGE3 2 3 0.0557936 2.41308 -0.0907328 0.000177213 -0.0159508 0.111957 +EDGE3 3 4 0.0329358 2.32759 -0.0910751 -0.0229219 -0.00723734 0.116474 +EDGE3 4 5 -0.0246424 2.43228 -0.0826252 0.036889 -0.00360582 0.106896 +EDGE3 5 6 -0.0441412 2.4152 -0.0450475 -0.000902747 0.0144355 0.0620788 +EDGE3 6 7 0.126405 2.52821 -0.0471717 0.0448278 0.0295693 0.115857 +EDGE3 7 8 0.174745 2.40918 -0.0978439 0.0345772 0.0433886 0.103089 +EDGE3 8 9 0.0920302 2.45716 -0.0624008 0.0199746 -0.00115823 0.118818 +EDGE3 9 10 0.1012 2.51161 0.0289767 -0.0393727 0.0187841 0.12601 +EDGE3 10 11 -0.0432916 2.55211 -0.0489115 0.0429138 -0.0345108 0.112142 +EDGE3 11 12 0.0323137 2.68638 0.0164828 -0.0208246 0.0329187 0.11095 +EDGE3 12 13 -0.0458792 2.46896 0.051913 0.0834607 0.00994417 0.163069 +EDGE3 13 14 0.028409 2.74036 0.154456 0.011377 0.00823426 0.0994095 +EDGE3 14 15 -0.255521 2.51875 -0.260493 -0.020439 -0.0115567 0.10063 +EDGE3 15 16 -0.207298 2.55606 -0.00750751 0.0288935 8.92498e-05 0.102035 +EDGE3 16 17 -0.0232232 2.62218 0.161642 -0.0117727 0.0142764 0.157621 +EDGE3 17 18 0.172624 2.82809 0.0200802 -0.0320181 -0.0186073 0.116387 +EDGE3 18 19 0.104784 2.60351 -0.165277 -0.00359431 -0.0262071 0.092372 +EDGE3 19 20 -0.00918021 2.89065 -0.00847865 0.0431695 -0.0180277 0.134949 +EDGE3 20 21 -0.00459382 2.86276 -0.0630594 -0.0083998 0.00714964 0.100628 +EDGE3 21 22 0.033076 2.8195 0.0638549 -0.0158611 0.0143183 0.115772 +EDGE3 22 23 -0.0280515 2.77973 -0.0805694 -0.0116863 0.0122267 0.114286 +EDGE3 23 24 0.23428 2.76917 -0.0230835 0.0441419 -0.0161249 0.109122 +EDGE3 24 25 -0.0571718 2.76825 0.124032 -0.0240298 -0.0603932 0.121259 +EDGE3 25 26 -0.0637599 2.74527 -0.0293876 -0.0168431 0.0173628 0.128587 +EDGE3 27 26 -0.386467 -2.72002 0.112517 -0.0293406 0.0297129 -0.160592 +EDGE3 28 27 -0.35837 -2.81956 0.111961 0.00796789 -0.0169516 -0.132868 +EDGE3 29 28 -0.215582 -2.88708 0.0849365 -0.0271487 0.0302639 -0.109097 +EDGE3 30 29 -0.300383 -2.69956 0.0568224 0.00118963 -0.0290945 -0.0838263 +EDGE3 31 30 -0.452357 -3.01403 -0.112578 0.0336296 0.017111 -0.119611 +EDGE3 32 31 -0.303143 -2.82183 0.0723764 0.0117906 0.0072254 -0.156743 +EDGE3 33 32 -0.573439 -2.85446 0.134837 -0.00948703 0.00664943 -0.147758 +EDGE3 34 33 -0.342564 -2.81535 0.037161 0.00365999 -0.00139288 -0.139315 +EDGE3 35 34 -0.392514 -2.71287 0.0429635 0.0114237 0.044421 -0.142207 +EDGE3 36 35 -0.501577 -2.93792 0.04093 0.0201385 -0.0232079 -0.145391 +EDGE3 37 36 -0.370257 -2.9791 0.035805 -0.0237647 -0.0103308 -0.118169 +EDGE3 38 37 -0.0829781 -3.11147 0.0302124 0.0470629 0.0098856 -0.0937817 +EDGE3 39 38 -0.292685 -2.68255 0.0321595 0.00364105 -0.00773812 -0.119864 +EDGE3 40 39 -0.330289 -2.88119 0.0464991 -0.0108285 -0.00510689 -0.140758 +EDGE3 41 40 -0.227377 -2.9709 -0.0179701 0.038939 0.0332026 -0.0572276 +EDGE3 42 41 -0.21224 -2.91837 -0.232378 0.055362 -0.0612021 -0.112429 +EDGE3 43 42 -0.525825 -2.92151 -0.0550979 0.0159841 0.0340644 -0.167465 +EDGE3 44 43 -0.274194 -3.00492 -0.111905 0.00780266 0.010964 -0.153163 +EDGE3 45 44 -0.353819 -2.99966 0.0250547 0.0120463 0.0153602 -0.129819 +EDGE3 46 45 -0.33367 -2.92216 -0.136702 0.0102404 -0.0292803 -0.125359 +EDGE3 47 46 -0.311254 -2.97259 0.0792712 -0.0122079 -0.014873 -0.108863 +EDGE3 48 47 -0.459223 -3.24941 0.122781 0.000278327 -0.0139984 -0.151906 +EDGE3 49 48 -0.363993 -3.2445 -0.135323 0.0152571 -0.00060928 -0.122627 +EDGE3 50 49 -0.348649 -3.04902 -0.113275 0.0205495 0.0279895 -0.109262 +EDGE3 50 51 -0.0886201 3.21568 -0.0264528 -0.000214552 0.016896 0.0879504 +EDGE3 51 52 0.063002 3.26176 -0.00684437 -0.0146257 -0.0354942 0.111862 +EDGE3 52 53 -0.0557637 3.17409 0.0734774 0.0709498 0.0288949 0.105063 +EDGE3 53 54 -0.108727 3.24709 -0.0137857 -0.0226472 0.0251277 0.0593623 +EDGE3 54 55 -0.0249343 3.06161 -0.132549 0.00100221 0.0140341 0.102152 +EDGE3 55 56 -0.105718 3.14621 -0.177419 -0.0211034 0.00969485 0.134409 +EDGE3 56 57 -0.0705069 3.21174 0.01297 -0.0388077 0.0366992 0.128814 +EDGE3 57 58 -0.308481 3.23319 -0.0291353 -0.0268371 0.00527244 0.100488 +EDGE3 58 59 -0.141402 3.27307 -0.0251842 -0.0205711 0.0169529 0.182837 +EDGE3 59 60 0.0213947 3.14314 -0.145891 0.0272168 -0.00321541 0.181868 +EDGE3 60 61 0.0553422 3.42191 0.0226578 0.000485278 0.0170686 0.119882 +EDGE3 61 62 -0.0876106 3.43325 -0.0604015 0.0315106 -0.0143553 0.133301 +EDGE3 62 63 -0.0231087 3.33901 -0.048245 -0.01919 0.0269634 0.0893058 +EDGE3 63 64 -0.173162 3.41663 -0.0409807 0.00179984 -0.0224518 0.115081 +EDGE3 64 65 0.0750887 3.36666 -0.00884558 0.0185089 -0.000408084 0.132289 +EDGE3 65 66 -0.318426 3.53535 0.0236881 0.0552963 -0.00696908 0.154044 +EDGE3 66 67 -0.309377 3.45796 -0.0860191 -0.0211663 0.00841756 0.0671391 +EDGE3 67 68 -0.0971846 3.40725 0.0457422 -0.00494101 -0.0430919 0.0839735 +EDGE3 68 69 -0.0796663 3.4423 -0.0600108 0.0285404 0.00307746 0.117533 +EDGE3 69 70 -0.165549 3.56416 0.0506461 -0.00239879 -0.00239417 0.16383 +EDGE3 70 71 -0.0136551 3.43078 -0.133598 0.00967105 -0.00759251 0.121395 +EDGE3 71 72 -0.0975885 3.49352 -0.0818545 0.0272017 0.0132885 0.142509 +EDGE3 72 73 -0.112144 3.48107 0.0107524 -0.0252711 0.00661745 0.154767 +EDGE3 73 74 -0.160196 3.45397 -0.0511834 0.00229982 -0.00639532 0.102674 +EDGE3 74 75 -0.282206 3.60103 0.0468579 0.00620231 -0.0138812 0.112074 +EDGE3 75 76 0.0905726 3.44264 0.0529876 -0.02339 0.0432606 0.155551 +EDGE3 76 77 -0.18962 3.51291 0.00250796 0.0620965 -0.0202881 0.164875 +EDGE3 77 78 -0.202746 3.61235 -0.155095 -0.0136941 -0.0180363 0.0797913 +EDGE3 78 79 -0.182209 3.80077 -0.152645 0.0285578 0.00892133 0.15202 +EDGE3 79 80 -0.2676 3.51719 0.037503 -0.0302086 0.0195235 0.0998354 +EDGE3 80 81 -0.0943781 3.5582 0.0260418 -0.0141752 -0.00114926 0.149545 +EDGE3 81 82 -0.153905 3.6196 -0.0831981 -0.024463 -0.018801 0.106203 +EDGE3 82 83 -0.0511099 3.50428 0.0805038 0.00321157 0.0320512 0.133777 +EDGE3 83 84 -0.110098 3.67012 0.0566261 0.0193253 -0.00966843 0.128798 +EDGE3 84 85 0.150045 3.65128 -0.165603 0.0193725 -0.0249613 0.130933 +EDGE3 85 86 -0.0750947 3.65015 -0.0738416 0.0087435 -0.0229523 0.142259 +EDGE3 86 87 -0.152509 3.66838 -0.125702 0.0170946 -0.018765 0.0955062 +EDGE3 87 88 -0.210828 3.60356 0.0387055 0.0185886 -0.0144925 0.122519 +EDGE3 88 89 -0.237042 3.73872 0.0621342 0.0281414 0.0132942 0.174402 +EDGE3 89 90 -0.0659852 3.62327 -0.163814 0.0457237 0.025888 0.128578 +EDGE3 90 91 -0.0755625 3.88051 -0.141069 0.040632 -0.022785 0.129242 +EDGE3 91 92 -0.125054 3.93774 0.152497 -0.0179436 -0.0259232 0.135525 +EDGE3 92 93 -0.171306 3.98819 -0.0564251 -0.0144252 -0.00732604 0.101429 +EDGE3 93 94 -0.0531429 3.79977 -0.0968367 0.0241054 -0.0287072 0.164231 +EDGE3 94 95 -0.213337 3.91223 -0.0196613 -0.0271055 0.00191728 0.129472 +EDGE3 95 96 -0.164284 3.86593 -0.0470053 -0.000387943 0.00940256 0.145048 +EDGE3 96 97 -0.0911524 3.82732 -0.0705018 0.00217022 -0.0153075 0.102982 +EDGE3 97 98 -0.0762562 3.77685 -0.0689707 0.00757101 -0.0174396 0.180875 +EDGE3 98 99 -0.126096 3.90627 0.218151 -0.0215133 -0.0223877 0.104291 +EDGE3 99 100 -0.19657 3.85101 -0.148813 -0.0322272 0.0245035 0.11489 +EDGE3 100 101 -0.20423 3.78051 -0.06825 0.0350258 0.0165113 0.149537 +EDGE3 101 102 -0.344937 3.76706 -0.0943634 0.0166364 -0.0131174 0.0705575 +EDGE3 102 103 -0.14548 3.99729 -0.088884 0.00699129 -0.0199978 0.150397 +EDGE3 103 104 -0.149122 4.08855 0.0296653 0.00249468 0.00680085 0.127341 +EDGE3 104 105 -0.312816 3.94794 -0.0316304 0.0115394 0.0282431 0.0840934 +EDGE3 105 106 -0.289434 3.96915 0.0778426 0.0324076 0.0371659 0.102094 +EDGE3 106 107 -0.308684 4.09533 -0.0487997 0.00639588 -0.0484115 0.123161 +EDGE3 107 108 -0.0852886 4.06372 -0.0590066 -0.0143034 0.00214382 0.144228 +EDGE3 108 109 -0.056877 4.00889 -0.00679841 0.0198124 -0.0292408 0.130576 +EDGE3 109 110 -0.181533 4.10299 0.0131423 -0.0297673 -0.00261885 0.167454 +EDGE3 110 111 -0.400916 3.80665 -0.0874299 0.023104 -0.00360747 0.17231 +EDGE3 111 112 -0.1297 3.94953 -0.127398 0.0368532 0.00590058 0.11817 +EDGE3 112 113 0.0459538 3.92951 -0.166167 -0.0326106 -0.00250775 0.120093 +EDGE3 113 114 -0.243649 4.08725 0.00557096 -0.00728232 -0.0128223 0.147401 +EDGE3 114 115 -0.32401 4.20696 -0.107443 -0.0416876 0.0161834 0.11112 +EDGE3 115 116 0.015186 4.16084 -0.0269265 -0.0105456 -0.00453071 0.0944201 +EDGE3 116 117 -0.134025 4.18648 -0.130159 0.0234535 0.0222454 0.110573 +EDGE3 117 118 -0.135213 4.2278 -0.152068 0.0222367 -0.0270057 0.077513 +EDGE3 118 119 -0.19008 4.09412 -0.0884868 0.00721055 -0.0416622 0.143695 +EDGE3 119 120 0.0358051 4.06397 -0.185127 -0.0340904 -0.00425677 0.103772 +EDGE3 120 121 -0.151363 4.2604 -0.101765 -0.0214325 -0.0170534 0.094002 +EDGE3 121 122 -0.299053 4.46516 0.120951 -0.0227337 0.0344527 0.129506 +EDGE3 122 123 -0.0984725 4.2376 0.0435968 -0.0138749 0.011999 0.0695923 +EDGE3 123 124 -0.102902 4.40859 0.0281922 -0.0142061 -0.0113519 0.0842801 +EDGE3 124 125 -0.134992 4.144 -0.0690061 0.0309679 -0.0199303 0.116839 +EDGE3 125 126 -0.182781 4.25239 0.0834474 -0.0173434 -0.0209024 0.158314 +EDGE3 126 127 -0.0689352 4.19323 -0.0569205 0.0558599 0.000818794 0.135913 +EDGE3 127 128 -0.126881 4.2556 -0.127496 0.00975383 -0.0067199 0.0912189 +EDGE3 128 129 -0.200728 4.29767 -0.0911094 0.0187601 0.0213499 0.139639 +EDGE3 129 130 -0.138033 4.33834 0.100025 -0.00948774 0.0326693 0.110684 +EDGE3 130 131 -0.066077 4.27212 0.0656955 0.00546449 -0.0157767 0.140902 +EDGE3 131 132 -0.272859 4.33127 -0.0550355 0.0246522 -0.0284517 0.140479 +EDGE3 132 133 -0.21487 4.48746 -0.150587 0.0218374 -0.0474505 0.131947 +EDGE3 133 134 -0.134073 4.39316 0.0771663 -0.0392448 0.00470948 0.124585 +EDGE3 134 135 -0.0224035 4.44216 -0.0946582 -0.010292 -0.0344783 0.133732 +EDGE3 135 136 -0.191931 4.52107 0.0350766 0.016454 0.00787966 0.171414 +EDGE3 136 137 -0.137611 4.39735 -0.0477466 0.0176583 -0.000941463 0.155746 +EDGE3 137 138 -0.101065 4.23609 0.0901895 0.0410279 0.0197357 0.120103 +EDGE3 138 139 -0.159007 4.4015 -0.0498357 7.32788e-05 -0.0378347 0.139843 +EDGE3 139 140 -0.275202 4.48776 0.034439 -0.0169564 0.0204812 0.130544 +EDGE3 140 141 -0.159022 4.42229 0.0616493 -0.00454529 -0.000856909 0.107349 +EDGE3 141 142 -0.272201 4.51234 -0.0947978 0.0117618 0.0368787 0.0839234 +EDGE3 143 144 -0.255482 4.51575 -0.0739281 -0.028103 -0.00495913 0.155526 +EDGE3 142 143 -0.097304 4.58142 -0.0736633 -0.0320536 0.0104575 0.100456 +EDGE3 144 145 -0.385323 4.59499 -0.121908 0.0247199 0.025731 0.101292 +EDGE3 145 146 -0.206457 4.50356 -0.0602837 0.0197184 -0.00273717 0.0823597 +EDGE3 146 147 -0.18928 4.61647 -0.0325388 -0.0151648 -0.00386753 0.139787 +EDGE3 147 148 -0.386073 4.54645 0.0632019 -0.0131948 0.00377531 0.106561 +EDGE3 148 149 -0.147303 4.57143 0.0419046 0.0252386 0.0387545 0.142836 +EDGE3 149 150 -0.118035 4.68216 -0.0521234 -0.0116969 -0.00274196 0.130723 +EDGE3 150 151 -0.339267 4.45238 -0.0541226 -0.00163232 -0.0237458 0.0845283 +EDGE3 151 152 -0.243219 4.51817 -0.0146676 0.0136779 -0.0258474 0.116357 +EDGE3 152 153 -0.0781915 4.85099 -0.0140594 0.0196969 -0.0166335 0.114992 +EDGE3 153 154 -0.240721 4.59969 -0.217156 -0.00862397 0.0213331 0.141065 +EDGE3 154 155 -0.142871 4.83704 -0.0642088 0.00577313 -0.0395843 0.114089 +EDGE3 156 157 -0.29275 4.76278 0.120575 0.0385443 0.0183706 0.0863786 +EDGE3 155 156 -0.15659 4.68608 0.105994 -0.0240786 0.00518535 0.139893 +EDGE3 158 159 -0.299824 4.71138 -0.193589 0.0288563 0.0060698 0.106073 +EDGE3 157 158 -0.028912 4.75216 0.0677388 0.0122943 0.0369683 0.121612 +EDGE3 160 161 -0.243643 4.65001 -0.120949 0.0317491 0.010423 0.0666234 +EDGE3 159 160 -0.262292 4.76241 0.0410303 0.0189934 0.0297567 0.13968 +EDGE3 162 163 -0.198378 4.66298 -0.00438035 0.013954 -0.0543858 0.108956 +EDGE3 161 162 -0.252329 4.70628 0.00806183 -0.0111775 -0.00767887 0.122225 +EDGE3 164 165 -0.240054 4.9405 -0.0138128 0.0405259 -0.0335959 0.100304 +EDGE3 163 164 -0.0267818 4.79204 0.0403253 -0.0110744 0.0045597 0.131009 +EDGE3 166 167 -0.168398 4.9929 -0.118626 -0.0190328 -0.0239155 0.110258 +EDGE3 165 166 -0.197095 4.81149 -0.0330859 0.0150544 0.0259011 0.137913 +EDGE3 168 169 -0.18715 4.90632 -0.0718764 0.0422783 -0.0156785 0.137961 +EDGE3 167 168 -0.270621 4.89055 -0.0383258 -0.00988663 0.03459 0.116952 +EDGE3 170 171 -0.292729 4.99474 -0.209804 0.0137478 -0.00416969 0.105009 +EDGE3 169 170 -0.152504 4.868 0.114387 -0.00621294 0.0219811 0.13889 +EDGE3 172 173 -0.265749 5.01558 0.1494 -0.00237613 -0.0146942 0.139835 +EDGE3 171 172 -0.220358 4.93485 0.0323752 -0.032323 -0.0300738 0.115408 +EDGE3 174 175 -0.282261 4.86028 -0.132406 -0.0152879 -0.0115124 0.130259 +EDGE3 173 174 -0.186445 4.87784 -0.274047 0.0275943 -0.00343321 0.105444 +EDGE3 176 177 -0.0438111 4.98778 -0.0464294 -0.0118425 -0.00815569 0.0927031 +EDGE3 175 176 -0.115254 5.13221 -0.0981557 -0.016045 -0.00869769 0.124088 +EDGE3 177 178 -0.260288 5.18088 0.13145 -0.00196104 0.0344686 0.146702 +EDGE3 178 179 -0.128284 5.05343 -0.0894707 -0.00256193 0.015808 0.142937 +EDGE3 179 180 -0.20451 5.03758 -0.144187 0.0114089 0.0176209 0.120633 +EDGE3 180 181 -0.10932 5.15666 -0.203533 -0.00418625 -0.0345385 0.127748 +EDGE3 181 182 -0.137429 4.95756 0.111282 0.0666966 0.014501 0.138999 +EDGE3 182 183 -0.128894 5.11948 -0.0746981 -0.0196952 0.0335056 0.117457 +EDGE3 183 184 -0.0426974 5.26807 0.00722057 -0.00268944 0.00228903 0.121203 +EDGE3 184 185 -0.176608 5.15589 0.105139 -0.0196593 0.0219684 0.171487 +EDGE3 185 186 -0.0724968 5.33276 0.0953149 -0.0344686 -0.000414231 0.15386 +EDGE3 186 187 -0.170391 5.1262 -0.0197287 0.0179753 0.0126892 0.161331 +EDGE3 187 188 -0.206124 5.08518 -0.0756103 0.0285042 -0.0245537 0.146681 +EDGE3 188 189 -0.159074 5.20131 -0.0249554 -0.00877015 0.0349892 0.108252 +EDGE3 189 190 -0.19152 5.16404 -0.145727 -0.0453383 -0.0106902 0.155328 +EDGE3 190 191 -0.304567 5.14359 -0.0854163 0.019153 -0.00908424 0.101875 +EDGE3 191 192 -0.069315 5.24923 -0.127874 0.0147642 -0.00140473 0.140956 +EDGE3 192 193 -0.181774 5.18485 0.0353037 -0.0160255 0.0300726 0.154863 +EDGE3 193 194 -0.349823 5.28889 0.0862399 0.0276565 0.0423226 0.11623 +EDGE3 194 195 -0.266975 5.32905 0.120325 -0.0228959 0.00404313 0.148293 +EDGE3 195 196 -0.176757 5.21125 -0.118905 0.0514739 -0.0203354 0.101833 +EDGE3 196 197 -0.192456 5.32629 -0.162274 0.00583045 0.025454 0.142682 +EDGE3 197 198 -0.0375575 5.39605 -0.0660908 -0.00396299 -0.00171043 0.107452 +EDGE3 198 199 -0.261083 5.28004 0.0197804 -0.0222015 -0.0141646 0.132872 +EDGE3 199 200 -0.154357 5.307 -0.0599985 0.0510435 -0.0210083 0.165102 +EDGE3 200 201 -0.18301 5.23617 0.179408 0.0147445 -0.0337847 0.145137 +EDGE3 201 202 -0.207534 5.45395 -0.0141131 -0.0100034 -0.0200326 0.0842041 +EDGE3 202 203 -0.0901731 5.32156 0.12452 0.0201203 0.00534604 0.158978 +EDGE3 203 204 -0.167935 5.44067 0.00570177 0.0178792 -0.0179276 0.10599 +EDGE3 204 205 -0.277681 5.38684 -0.0725682 0.0179784 0.0150085 0.122321 +EDGE3 205 206 -0.21396 5.42145 -0.0976752 -0.0125054 -0.0209873 0.133115 +EDGE3 206 207 -0.198938 5.2524 -0.0749508 0.00237304 -0.0240009 0.109479 +EDGE3 207 208 -0.225355 5.53694 -0.021574 -0.0145894 -0.00231135 0.16542 +EDGE3 208 209 -0.271788 5.55949 -0.00998529 0.00653119 -0.0124467 0.141473 +EDGE3 209 210 -0.123474 5.49317 -0.0142897 -0.0273656 0.0139248 0.125765 +EDGE3 210 211 -0.31667 5.60524 -0.230642 -0.00351458 0.0335388 0.135207 +EDGE3 211 212 -0.429308 5.55196 0.176962 0.0717385 -0.00108499 0.13023 +EDGE3 212 213 -0.294454 5.54343 -0.0738791 0.00805116 -0.0520405 0.0961659 +EDGE3 213 214 -0.127386 5.46526 0.0173131 -0.0364378 0.0378839 0.131557 +EDGE3 214 215 -0.0953996 5.68339 -0.0235317 -1.1317e-05 0.0263273 0.103308 +EDGE3 215 216 -0.153878 5.67983 -0.0843109 0.0306884 0.00214383 0.120359 +EDGE3 216 217 -0.0316685 5.50859 -0.150817 -0.0260768 -0.0352015 0.133498 +EDGE3 217 218 -0.360676 5.6911 0.0319997 -0.0049324 0.0127573 0.135087 +EDGE3 218 219 -0.276267 5.49165 -0.0382517 -0.00574681 -0.000528913 0.14361 +EDGE3 219 220 -0.201916 5.53677 -0.0608488 0.0118859 0.00586753 0.1262 +EDGE3 220 221 -0.17791 5.68525 0.00654041 0.0110899 0.00331986 0.109356 +EDGE3 221 222 -0.0718961 5.69822 -0.0407743 -0.0016869 -0.0321656 0.169673 +EDGE3 222 223 -0.250475 5.59282 -0.0705694 0.021158 0.0297186 0.135155 +EDGE3 223 224 -0.185195 5.66279 0.057013 -0.00277035 -0.014198 0.114482 +EDGE3 224 225 -0.0449758 5.8838 -0.0245691 0.0234626 0.0079427 0.119976 +EDGE3 225 226 -0.241206 5.83895 0.0180653 0.0161452 -0.0183924 0.0953997 +EDGE3 226 227 -0.207589 5.5903 -0.0287962 -0.0516147 -0.0183791 0.108106 +EDGE3 227 228 -0.265743 5.95296 -0.0885802 0.0100804 0.0331044 0.118104 +EDGE3 228 229 -0.205391 5.72913 -0.250733 -0.00508861 0.018364 0.132151 +EDGE3 229 230 -0.41706 5.63978 -0.174954 0.0431777 0.00261166 0.119334 +EDGE3 230 231 -0.11708 5.86131 0.0807168 0.0227041 -0.0151595 0.137597 +EDGE3 231 232 -0.253704 6.00866 0.167756 -0.00584601 -0.0170768 0.120421 +EDGE3 232 233 -0.09401 5.84826 -0.15422 0.0135274 -0.0114439 0.109624 +EDGE3 233 234 -0.278448 5.65642 -0.0121759 0.0319552 -0.000653121 0.0965139 +EDGE3 234 235 -0.139914 5.88256 -0.157413 -0.0082663 -0.0155741 0.132386 +EDGE3 235 236 -0.12009 5.74838 -0.22755 0.0537052 0.0172294 0.104256 +EDGE3 236 237 -0.260112 5.82256 -0.00885689 0.063814 0.0266587 0.13616 +EDGE3 237 238 -0.29173 5.89892 -0.158266 0.0380039 0.00659016 0.150315 +EDGE3 238 239 -0.285701 5.8673 0.0554619 0.0131379 -0.00426412 0.128867 +EDGE3 239 240 -0.265612 5.87949 -0.0251238 0.0206753 0.0317912 0.128765 +EDGE3 240 241 -0.123536 5.83636 -0.0627261 -0.044028 -0.00918571 0.10167 +EDGE3 241 242 -0.203755 6.03092 -0.0767133 -0.00740014 0.0373389 0.131151 +EDGE3 242 243 -0.221696 5.90483 -0.150491 0.0112752 -0.0156589 0.151316 +EDGE3 243 244 -0.313655 5.78523 0.0234292 0.0152533 -0.0327036 0.131037 +EDGE3 244 245 -0.196634 6.11515 0.0338495 0.0149984 0.00680414 0.129316 +EDGE3 245 246 -0.260782 5.856 0.0582826 -0.04272 -0.00991024 0.154523 +EDGE3 246 247 -0.229033 5.90092 -0.117842 0.0105775 0.000103767 0.114672 +EDGE3 247 248 -0.165909 6.02486 -0.268601 0.015611 -0.0416227 0.119997 +EDGE3 248 249 -0.476145 5.99729 -0.0593761 -0.00577091 0.0667937 0.103867 +EDGE3 249 250 -0.147093 6.27639 -0.163905 -0.0309321 0.0117725 0.0844452 +EDGE3 250 251 -0.306841 5.98168 0.0782619 0.0267528 0.0060458 0.114936 +EDGE3 251 252 -0.188074 6.1932 0.0220776 0.00224128 0.00855477 0.118151 +EDGE3 252 253 -0.290927 6.11527 -0.0316084 -0.0342139 0.00106036 0.120249 +EDGE3 253 254 -0.306348 6.16344 -0.00449441 0.0128476 0.0310485 0.141298 +EDGE3 254 255 -0.289866 6.23757 0.0179525 0.0309225 0.00777286 0.101842 +EDGE3 255 256 -0.311617 6.05838 0.0144193 0.00125611 -0.00190156 0.0952534 +EDGE3 256 257 -0.299391 6.27975 -0.0137484 0.00297409 -0.0148299 0.110673 +EDGE3 257 258 -0.407112 6.09062 0.203572 -0.0182518 -0.0162262 0.121533 +EDGE3 258 259 -0.342489 6.16495 -0.0776685 -0.00312932 0.0131473 0.128296 +EDGE3 259 260 -0.518559 6.29251 -0.186837 0.00951991 0.0115848 0.132184 +EDGE3 260 261 -0.374513 6.0136 -0.0769947 0.0248762 0.0234757 0.13874 +EDGE3 261 262 -0.263125 6.09461 -0.0216502 -0.0696866 0.0136161 0.12007 +EDGE3 262 263 -0.461176 6.14063 -0.0145906 -0.00311276 -0.0105357 0.135609 +EDGE3 263 264 -0.198863 6.20898 -0.0892126 0.0298264 -0.0070054 0.153833 +EDGE3 264 265 -0.137828 6.26879 0.0251088 -0.0184647 0.0172799 0.180391 +EDGE3 265 266 -0.355581 6.18666 -0.129394 0.00167192 -0.043291 0.13191 +EDGE3 266 267 -0.210085 6.33182 -0.165093 0.00385954 0.0026185 0.149206 +EDGE3 267 268 -0.234599 6.11217 0.049536 -0.037364 -0.0122323 0.0920534 +EDGE3 268 269 -0.174787 6.35142 -0.176676 -0.0368132 0.0221748 0.132238 +EDGE3 269 270 -0.220475 6.47983 0.0799236 0.0192662 0.0377441 0.178708 +EDGE3 270 271 -0.305033 6.23089 -0.0660993 -0.0174429 -0.00285046 0.132673 +EDGE3 271 272 -0.226065 6.21834 0.149414 0.0404853 -0.0484581 0.0997897 +EDGE3 272 273 -0.116505 6.39546 -0.0859603 0.0216735 -0.0281443 0.155884 +EDGE3 273 274 -0.382225 6.37769 -0.0585425 0.0174617 0.0448119 0.132065 +EDGE3 274 275 -0.265045 6.43778 0.0528551 -0.0140606 5.03913e-05 0.122823 +EDGE3 275 276 -0.50521 6.25973 -0.139667 0.0412911 -0.00495785 0.105221 +EDGE3 276 277 -0.139287 6.36876 -0.0492238 0.046997 0.00194629 0.109231 +EDGE3 277 278 -0.291209 6.47977 -0.0922055 -0.00959331 -0.00868988 0.147266 +EDGE3 278 279 -0.271462 6.34679 -0.12973 0.0192379 0.0476055 0.151216 +EDGE3 279 280 -0.179483 6.43573 -0.163837 -0.0355744 0.0194119 0.0944955 +EDGE3 280 281 -0.315922 6.42081 -0.189789 -0.00478106 -0.0062045 0.126777 +EDGE3 281 282 -0.244814 6.39786 0.0244255 -0.0120658 0.0124054 0.0916939 +EDGE3 282 283 -0.188631 6.47975 -0.0429045 0.0110663 0.0284756 0.103994 +EDGE3 283 284 -0.3802 6.42411 -0.0240862 -0.0308488 -0.000716775 0.170119 +EDGE3 284 285 -0.315105 6.66071 -0.00671108 0.000619618 -0.0328924 0.17872 +EDGE3 285 286 -0.297076 6.2699 -0.0473597 -0.0352913 0.0168416 0.156064 +EDGE3 286 287 -0.364394 6.73693 -0.0649376 0.00423585 -0.0370471 0.0947235 +EDGE3 287 288 -0.301245 6.34139 -0.0543941 0.00644608 -0.0307823 0.143658 +EDGE3 288 289 -0.415957 6.40738 -0.0237532 -0.00711722 -0.0175969 0.13412 +EDGE3 289 290 -0.203709 6.62071 -0.0431002 0.00750846 0.00380843 0.201315 +EDGE3 290 291 -0.378004 6.48828 0.0126148 -0.0369936 -0.0169296 0.117075 +EDGE3 291 292 -0.373317 6.51582 -0.179085 0.00627607 0.04723 0.147726 +EDGE3 292 293 -0.49836 6.5099 -0.240885 0.0498283 0.0376378 0.125834 +EDGE3 293 294 -0.328326 6.60907 -0.27776 0.0246523 0.00762804 0.17008 +EDGE3 294 295 -0.288191 6.65589 -0.0697811 0.0272862 -0.0188782 0.0865777 +EDGE3 295 296 -0.208722 6.74618 -0.121642 0.0328034 0.00732636 0.117764 +EDGE3 296 297 -0.403886 6.56466 0.000471949 -0.0399555 -0.00836041 0.124855 +EDGE3 297 298 -0.291196 6.60875 -0.298389 -0.0145947 0.0281814 0.134794 +EDGE3 298 299 -0.447174 6.77839 -0.102871 0.0108042 0.005024 0.120044 +EDGE3 299 300 -0.441918 6.73804 -0.147716 0.0372278 -0.0104087 0.113026 +EDGE3 300 301 -0.345221 6.76053 -0.0790742 -0.00454523 -0.0454633 0.0875795 +EDGE3 301 302 -0.306963 6.79506 -0.021975 0.014399 -0.0252016 0.0672863 +EDGE3 302 303 -0.249519 7.02314 0.0885546 0.0174238 -0.0106512 0.160564 +EDGE3 303 304 -0.202091 6.74385 -0.0452568 -0.00612253 -0.00350822 0.128085 +EDGE3 304 305 -0.418033 6.56986 -0.099662 -0.00123412 0.00347393 0.129761 +EDGE3 305 306 -0.33336 6.86862 -0.181845 -0.0337862 0.0291422 0.0819294 +EDGE3 306 307 -0.341731 6.5602 -0.179031 0.0214415 0.00744373 0.126203 +EDGE3 307 308 -0.267374 6.7623 -0.0697621 0.00110004 0.0060061 0.132197 +EDGE3 308 309 -0.329307 6.86644 -0.0263814 0.0211008 -0.00737005 0.122007 +EDGE3 309 310 -0.31168 6.64336 -0.161507 0.0435947 0.032828 0.137195 +EDGE3 310 311 -0.397507 6.78392 -0.0968239 0.0244611 -0.00786954 0.121092 +EDGE3 311 312 -0.440273 6.93345 -0.139358 -0.0168342 -0.0208526 0.0822262 +EDGE3 312 313 -0.259345 6.86603 -0.00709458 -0.00700497 -0.0218923 0.10882 +EDGE3 313 314 -0.41427 6.81077 -0.23316 0.0197853 0.00975285 0.115905 +EDGE3 314 315 -0.365038 6.97567 0.00637845 -0.00408156 -0.00424793 0.10811 +EDGE3 315 316 -0.348294 7.07014 -0.0319342 0.0261802 -0.0129522 0.118167 +EDGE3 316 317 -0.34783 6.82512 -0.0755667 0.0261249 -0.0085242 0.120377 +EDGE3 317 318 -0.123984 6.77423 -0.12572 -0.00477777 0.00148744 0.127399 +EDGE3 318 319 -0.239918 6.98193 -0.230643 0.0022871 0.0117171 0.118388 +EDGE3 319 320 -0.319352 6.9193 0.144191 0.0112265 0.0076107 0.169197 +EDGE3 320 321 -0.399105 7.04384 0.0462207 -0.0150236 -0.016549 0.110241 +EDGE3 321 322 -0.564005 6.95406 -0.164822 -0.000716126 -0.0119039 0.0906097 +EDGE3 322 323 -0.447963 6.92362 -0.143051 -0.0241763 -0.00848537 0.109522 +EDGE3 323 324 -0.402428 6.95093 -0.146908 0.0166168 -0.0325103 0.146588 +EDGE3 324 325 -0.3593 6.96169 0.000771052 0.0698217 -0.0259074 0.0903649 +EDGE3 325 326 -0.314644 7.03789 -0.240565 0.0103167 -0.017128 0.0946256 +EDGE3 326 327 -0.327328 7.12381 -0.0679445 0.0159936 0.0183989 0.105554 +EDGE3 327 328 -0.241996 7.22495 0.127068 -0.0389857 0.00464302 0.130719 +EDGE3 328 329 -0.38789 6.98455 -0.2031 -0.0416603 -0.00368547 0.12432 +EDGE3 329 330 -0.359264 7.00691 -0.0816846 -0.0291695 -0.00742125 0.140793 +EDGE3 330 331 -0.381711 7.16197 0.0512942 -0.0111174 -0.0157115 0.147214 +EDGE3 331 332 -0.314497 7.20595 0.150845 0.0184514 0.00353971 0.089392 +EDGE3 332 333 -0.195221 7.10457 0.226581 0.0240019 -0.012737 0.122627 +EDGE3 333 334 -0.483872 6.98259 0.0846365 -0.0394022 -0.00613389 0.132791 +EDGE3 334 335 -0.174763 7.15678 0.0963808 0.00397314 0.0164767 0.0855997 +EDGE3 335 336 -0.513065 7.33157 0.0811313 0.0518754 -0.0166084 0.159407 +EDGE3 336 337 -0.460535 7.27088 -0.0746995 0.0661065 -0.0201173 0.160249 +EDGE3 337 338 -0.495268 7.12169 0.0239769 -0.00737198 0.00873455 0.115576 +EDGE3 338 339 -0.298193 7.09735 0.013873 0.0398327 0.0341804 0.17588 +EDGE3 339 340 -0.471672 7.28981 -0.168874 -0.00844272 0.0240478 0.105719 +EDGE3 340 341 -0.290982 7.10652 -0.154532 -0.031517 -0.0122867 0.131795 +EDGE3 341 342 -0.289588 7.38346 -0.0415564 -0.0181227 -0.00989775 0.156366 +EDGE3 342 343 -0.512159 7.40841 -0.0995836 -0.00195341 0.0105576 0.127667 +EDGE3 343 344 -0.327359 7.33888 0.00376917 0.0207776 0.0103706 0.155138 +EDGE3 344 345 -0.326594 7.24704 -0.0779745 -0.00107341 0.00144351 0.102142 +EDGE3 345 346 -0.324916 7.12867 0.0066772 0.00609143 0.0188474 0.105241 +EDGE3 346 347 -0.466736 7.24746 -0.105563 -0.0341224 0.0193462 0.115436 +EDGE3 347 348 -0.166151 7.21114 -0.0139893 -0.0182654 -0.0455993 0.0930972 +EDGE3 348 349 -0.343193 7.38308 -0.177468 0.0117456 0.0239018 0.17742 +EDGE3 349 350 -0.435881 7.35502 -0.00383498 0.0417073 -0.0527999 0.130515 +EDGE3 350 351 -0.424147 7.24712 0.0106165 0.0122323 0.0348256 0.148363 +EDGE3 351 352 -0.321421 7.42099 -0.236993 0.0189539 -0.0233557 0.138536 +EDGE3 352 353 -0.331285 7.29861 -0.128183 0.0227967 0.0538116 0.100242 +EDGE3 353 354 -0.294051 7.57864 -0.0508621 -0.00420202 -0.0489545 0.157267 +EDGE3 354 355 -0.318636 7.51158 0.00931779 0.00224477 -0.00921433 0.124864 +EDGE3 355 356 -0.38982 7.47294 -0.183408 -0.0175109 -0.0434762 0.124775 +EDGE3 356 357 -0.450535 7.47795 -0.127175 -0.0230318 -0.0180209 0.0513385 +EDGE3 357 358 -0.367346 7.42128 -0.19407 -0.0257274 -0.000995052 0.0915583 +EDGE3 358 359 -0.35183 7.53079 -0.0384286 0.0174051 -0.0138286 0.133187 +EDGE3 359 360 -0.362337 7.45021 0.095778 0.00490927 -0.0224211 0.14475 +EDGE3 360 361 -0.289407 7.34714 -0.212998 -0.0213031 -0.00416772 0.113496 +EDGE3 361 362 -0.398513 7.42867 -0.135834 0.0194426 -0.0127327 0.107113 +EDGE3 362 363 -0.467374 7.40511 0.117043 -0.0168589 0.031372 0.130347 +EDGE3 363 364 -0.430438 7.55523 -0.0896207 0.0527486 0.0107349 0.124064 +EDGE3 364 365 -0.44464 7.51521 -0.111201 -0.00259341 -0.0418141 0.132399 +EDGE3 365 366 -0.334993 7.63084 -0.130237 0.0133781 -0.0503707 0.19146 +EDGE3 366 367 -0.348949 7.62019 -0.0570106 0.0134576 0.011392 0.133942 +EDGE3 367 368 -0.369212 7.63824 -0.112723 0.0303205 0.00711482 0.0884786 +EDGE3 368 369 -0.60569 7.57312 0.0554561 -0.024587 0.0276736 0.102307 +EDGE3 369 370 -0.276132 7.70662 -0.0604016 -0.0205383 -0.0374382 0.107185 +EDGE3 370 371 -0.41593 7.59031 -0.107835 0.0320172 -0.0121835 0.0903998 +EDGE3 371 372 -0.519649 7.66616 -0.35216 0.00923389 0.00812977 0.132743 +EDGE3 372 373 -0.361941 7.75176 -0.0970457 -0.00414803 0.0232936 0.130094 +EDGE3 373 374 -0.365021 7.71616 -0.21589 -0.00766946 -0.0250347 0.158153 +EDGE3 374 375 -0.213179 7.56203 -0.176771 0.0409642 0.0203622 0.0692837 +EDGE3 375 376 -0.484104 7.74679 0.0654065 -0.0285554 0.00175926 0.159178 +EDGE3 376 377 -0.36053 7.78363 -0.0469128 -0.00927446 0.0348228 0.142195 +EDGE3 377 378 -0.60831 7.69588 -0.220311 -0.00346805 0.00128982 0.167409 +EDGE3 378 379 -0.539657 7.72185 -0.203823 -0.0145936 0.000264654 0.119391 +EDGE3 379 380 -0.49621 7.8573 0.0204334 0.0228932 -0.0544016 0.117059 +EDGE3 380 381 -0.340544 7.66679 -0.120353 0.00861942 0.00492649 0.130951 +EDGE3 381 382 -0.502971 7.79176 -0.127304 0.00399649 -0.00219746 0.0783963 +EDGE3 382 383 -0.461663 7.96204 0.0484136 0.0506863 -0.0115576 0.156771 +EDGE3 383 384 -0.352589 7.88395 -0.152792 0.00913233 -0.0172087 0.12202 +EDGE3 384 385 -0.338078 7.78747 0.0664706 0.000399229 -0.0264734 0.111816 +EDGE3 385 386 -0.438664 7.64666 -0.121845 0.0330983 -0.00643196 0.153259 +EDGE3 386 387 -0.456326 7.92971 -0.12803 -0.0330157 -0.00594895 0.174375 +EDGE3 387 388 -0.465092 7.90317 0.0333784 0.00447255 0.0447764 0.124025 +EDGE3 388 389 -0.461796 7.66644 -0.0240828 -0.011301 0.0223567 0.123412 +EDGE3 389 390 -0.433644 8.02876 -0.140436 -0.00800061 -0.00163427 0.119047 +EDGE3 390 391 -0.484512 7.88387 -0.0133902 0.00368255 -0.00601561 0.153059 +EDGE3 391 392 -0.450612 7.78232 0.0647279 -0.0187011 0.00368104 0.118386 +EDGE3 392 393 -0.416113 7.88317 -0.0806501 0.0148424 0.0112132 0.153255 +EDGE3 393 394 -0.213231 7.99549 0.00277645 -0.0311085 -0.0166296 0.0758448 +EDGE3 394 395 -0.361689 7.94116 -0.0429917 -0.0592402 -0.0238552 0.138727 +EDGE3 395 396 -0.307581 7.91512 -0.115812 0.0142473 -0.0062351 0.0952673 +EDGE3 396 397 -0.301425 7.82616 -0.00267573 0.029296 -0.00791017 0.122068 +EDGE3 397 398 -0.221977 8.20695 -0.0094634 -0.028754 -0.0172231 0.131358 +EDGE3 398 399 -0.427193 8.02193 0.0760342 0.0357997 0.0134089 0.0922434 +EDGE3 399 400 -0.599883 7.98856 -0.0814807 0.0247783 -0.0006705 0.116111 +EDGE3 400 401 -0.430841 8.11269 -0.0805113 -0.039502 0.0218786 0.116833 +EDGE3 401 402 -0.510491 7.89051 0.0936199 0.00695343 -0.0159469 0.0763351 +EDGE3 403 404 -0.38243 7.95766 -0.116497 -0.00268248 -0.0373247 0.119375 +EDGE3 402 403 -0.282788 8.17468 -0.122917 0.0278857 0.023823 0.139946 +EDGE3 404 405 -0.37098 8.04012 0.146353 0.0366774 0.000151369 0.158814 +EDGE3 405 406 -0.222215 7.90193 -0.0463443 0.0161802 -0.0451143 0.137556 +EDGE3 406 407 -0.255756 8.10085 -0.265487 0.0349962 -0.0212111 0.0955479 +EDGE3 407 408 -0.360968 7.84594 -0.101769 0.0120226 0.0241738 0.0836279 +EDGE3 408 409 -0.433919 8.00366 -0.265797 -0.00511802 0.00396629 0.102454 +EDGE3 409 410 -0.23413 7.97685 -0.246367 0.0527548 -0.0126535 0.129381 +EDGE3 410 411 -0.522892 8.17708 0.0757195 0.0361676 -0.0103683 0.122667 +EDGE3 411 412 -0.215494 8.07998 -0.0560468 -0.00219501 -0.0023633 0.156104 +EDGE3 412 413 -0.431862 8.2939 -0.0209909 -0.0206642 0.0353441 0.096709 +EDGE3 413 414 -0.289082 8.1301 -0.0437401 -0.0257984 -0.0502111 0.124169 +EDGE3 415 416 -0.437384 8.16679 -0.195404 -0.000248661 0.0284357 0.153092 +EDGE3 414 415 -0.281812 8.18002 -0.0346473 0.00280905 -0.0186126 0.131823 +EDGE3 417 418 -0.342633 7.90252 -0.00755947 0.00935774 -0.0153745 0.142144 +EDGE3 416 417 -0.382121 8.03039 -0.083664 -0.00525419 -0.0109717 0.153566 +EDGE3 419 420 -0.550505 8.33022 -0.0220178 0.0160033 -0.00731072 0.153742 +EDGE3 418 419 -0.317548 8.21024 0.0563052 0.0600606 0.0283211 0.174815 +EDGE3 421 422 -0.267462 8.14808 0.0747701 -0.0148343 0.000836764 0.111869 +EDGE3 420 421 -0.352911 8.31221 0.13358 -0.0389225 -0.00172561 0.110593 +EDGE3 423 424 -0.23902 8.33397 -0.214084 0.0126035 -0.0579096 0.148372 +EDGE3 422 423 -0.254086 8.25901 -0.0275482 -0.013612 -0.0223807 0.122398 +EDGE3 424 425 -0.349637 8.29754 0.104886 0.0268208 -0.00338755 0.117437 +EDGE3 425 426 -0.466595 8.17724 0.0328284 -0.0148383 -0.00552209 0.120946 +EDGE3 427 428 -0.327944 8.20628 0.0434102 -0.0104504 -0.0305986 0.0560338 +EDGE3 429 430 -0.24729 8.3572 -0.0637449 0.000234418 0.00291992 0.124359 +EDGE3 426 427 -0.322477 8.31157 -0.145061 0.0395717 0.020559 0.141934 +EDGE3 428 429 -0.372263 8.39966 -0.0688922 0.0437728 -0.00380981 0.148578 +EDGE3 431 432 -0.384125 8.40676 -0.0765537 -0.0198326 0.0368127 0.132825 +EDGE3 436 437 -0.268718 8.44329 -0.120604 0.0203313 0.00369001 0.0958537 +EDGE3 430 431 -0.262744 8.4217 -0.201423 0.0130343 0.0267576 0.128738 +EDGE3 433 434 -0.336028 8.43961 -0.12835 -0.0016515 0.0313221 0.116388 +EDGE3 432 433 -0.417435 8.5386 -0.124034 -0.008168 0.0220811 0.102224 +EDGE3 435 436 -0.473287 8.40719 -0.111323 -0.0145611 0.022009 0.0983852 +EDGE3 434 435 -0.458533 8.40616 -0.109733 0.0465909 0.0356733 0.0982615 +EDGE3 437 438 -0.467589 8.42459 -0.0846966 0.0058799 0.0278826 0.127137 +EDGE3 439 440 -0.355049 8.37392 -0.191231 -0.0017256 -0.0224864 0.10608 +EDGE3 438 439 -0.183057 8.47045 0.0165827 0.00440716 0.0399039 0.114469 +EDGE3 441 442 -0.440014 8.32316 0.0751723 0.00798134 0.0316293 0.139444 +EDGE3 440 441 -0.515284 8.316 -0.0134315 0.0423165 -0.000218951 0.118725 +EDGE3 443 444 -0.263655 8.54026 -0.0588436 0.00138821 0.0105152 0.0648383 +EDGE3 442 443 -0.487613 8.51892 -0.0863076 0.00364204 -0.00182546 0.172867 +EDGE3 445 446 -0.437614 8.48113 -0.159538 -0.00904871 -0.011935 0.104976 +EDGE3 444 445 -0.437261 8.56933 -0.128224 0.000991035 0.0182145 0.136707 +EDGE3 447 448 -0.565332 8.61757 -0.0370061 -0.00386988 0.0360681 0.101336 +EDGE3 446 447 -0.572918 8.37567 0.0385506 -0.00667776 -0.0280234 0.142535 +EDGE3 449 450 -0.541756 8.64418 -0.156552 0.0162982 -0.00629936 0.161229 +EDGE3 448 449 -0.452174 8.54732 -0.101602 0.0365854 0.00286452 0.152606 +EDGE3 451 452 -0.347272 8.60958 0.0328558 -0.040003 -0.0234987 0.125116 +EDGE3 450 451 -0.601967 8.73047 -0.0298237 -0.0255084 -0.00189225 0.153175 +EDGE3 453 454 -0.589468 8.77247 0.138391 -0.0162598 -0.0204174 0.0873047 +EDGE3 452 453 -0.568865 8.44027 0.123681 -0.00520777 0.0142177 0.100941 +EDGE3 455 456 -0.535613 8.82371 -0.0763683 0.00217258 -0.0125038 0.113213 +EDGE3 454 455 -0.58811 8.44701 0.0668973 0.0372283 0.0102666 0.154915 +EDGE3 457 458 -0.256188 8.73948 -0.12757 -0.0369256 0.0136276 0.13116 +EDGE3 456 457 -0.522493 8.54065 -0.124454 -0.0379307 0.0142894 0.178268 +EDGE3 459 460 -0.353645 8.54842 -0.0157639 0.0178955 0.00523677 0.155109 +EDGE3 458 459 -0.515442 8.70522 -0.182895 -0.025918 -0.0390726 0.118065 +EDGE3 461 462 -0.354431 8.9698 -0.146955 0.00466264 0.00260255 0.161032 +EDGE3 460 461 -0.596404 8.56173 -0.0108794 0.0282405 0.0547754 0.115589 +EDGE3 463 464 -0.409111 8.82506 -0.0980703 0.0336059 -0.00871474 0.132945 +EDGE3 462 463 -0.398452 8.67786 -0.111927 -0.0353116 -0.0171325 0.154703 +EDGE3 465 466 -0.445378 8.73539 -0.103833 0.0301955 -0.00448571 0.148343 +EDGE3 464 465 -0.489933 8.78312 -0.111033 0.0388942 0.0226806 0.113417 +EDGE3 466 467 -0.43498 8.53986 -0.0806792 -0.0110679 0.026869 0.118985 +EDGE3 467 468 -0.69459 8.69643 -0.061953 0.0101418 -0.0249657 0.114346 +EDGE3 468 469 -0.337617 8.82595 -0.0524814 -0.0059929 -0.0177854 0.0951108 +EDGE3 469 470 -0.454443 8.93918 -0.0503985 -0.0124927 0.037068 0.165459 +EDGE3 470 471 -0.465247 8.92013 -0.163899 0.0240518 0.000860826 0.141848 +EDGE3 471 472 -0.464433 8.61186 -0.160517 0.00111495 -0.020857 0.0912254 +EDGE3 472 473 -0.413722 8.7452 -0.163814 -0.038652 0.000401327 0.146031 +EDGE3 473 474 -0.486992 8.7851 -0.232136 0.00712578 -0.0113172 0.111992 +EDGE3 474 475 -0.574006 8.82327 -0.061089 -0.00969662 -0.0300251 0.0595619 +EDGE3 475 476 -0.366638 8.81534 -0.256391 -0.00895192 -0.0307831 0.138637 +EDGE3 476 477 -0.506603 8.86427 -0.223392 -0.0177369 -0.00737143 0.108261 +EDGE3 477 478 -0.572177 8.87267 -0.0521832 -0.000187405 -0.0559154 0.131358 +EDGE3 478 479 -0.514755 8.84958 -0.333054 -0.028547 -0.0247071 0.109534 +EDGE3 479 480 -0.55578 8.93466 -0.123499 -0.00644457 -0.0397195 0.166562 +EDGE3 480 481 -0.34408 9.07796 -0.307937 0.0250893 0.00928829 0.146185 +EDGE3 481 482 -0.427784 8.70292 -0.158329 -0.00203107 0.0167213 0.120012 +EDGE3 482 483 -0.493023 9.01167 -0.0966264 -0.012913 -0.0377006 0.126077 +EDGE3 483 484 -0.48568 9.05593 0.0399712 -0.00972107 0.072696 0.115236 +EDGE3 484 485 -0.299056 9.02511 -0.168671 0.00579021 -0.0216768 0.106628 +EDGE3 485 486 -0.476042 8.87354 0.0555164 0.00168605 -0.00261282 0.122487 +EDGE3 486 487 -0.734916 8.88152 -0.218934 -0.018971 -0.0109556 0.113967 +EDGE3 487 488 -0.555044 9.06573 -0.00155804 -0.0153195 -0.021958 0.130199 +EDGE3 488 489 -0.522393 8.844 -0.0687633 0.0382916 0.0299628 0.100833 +EDGE3 489 490 -0.370167 9.15574 -0.144327 -0.00238295 0.0186785 0.146947 +EDGE3 490 491 -0.493346 8.98223 -0.0762153 -0.0335898 -0.0414022 0.128782 +EDGE3 491 492 -0.445487 9.21843 -0.218112 -0.00844879 -0.0220795 0.1522 +EDGE3 492 493 -0.542594 9.14072 0.0839263 0.021215 -0.0264453 0.125125 +EDGE3 493 494 -0.39901 9.31731 -0.303058 -0.011686 0.0154655 0.132133 +EDGE3 494 495 -0.575162 9.12137 0.006909 0.0448272 -0.0305856 0.134666 +EDGE3 495 496 -0.546822 9.13005 -0.0302824 0.0367385 -0.0282096 0.152368 +EDGE3 496 497 -0.379396 9.19432 0.0362434 0.0253803 -0.0357325 0.126904 +EDGE3 497 498 -0.552156 9.13659 -0.117194 -0.00609656 -0.000972302 0.129734 +EDGE3 498 499 -0.457165 9.01459 -0.121282 -0.0126682 -0.00728707 0.118066 +EDGE3 499 500 -0.43803 9.31174 -0.0766824 0.0411612 -0.0040434 0.176417 +EDGE3 500 501 -0.569857 9.26711 -0.0300711 -0.00379863 0.0178006 0.117924 +EDGE3 501 502 -0.437069 9.25257 0.0926344 0.0263895 0.0335336 0.162987 +EDGE3 502 503 -0.552879 9.186 0.0698416 -0.00745889 0.000806748 0.141751 +EDGE3 503 504 -0.686667 9.27159 -0.160943 -0.00914751 0.0430203 0.0984795 +EDGE3 504 505 -0.45831 9.45354 -0.130343 -0.0112251 -0.0277202 0.111636 +EDGE3 505 506 -0.338601 9.0729 0.0410798 -0.00251065 -0.0212787 0.107336 +EDGE3 506 507 -0.476825 9.06218 0.0595855 -0.0110154 0.011024 0.146084 +EDGE3 507 508 -0.446877 9.28334 -0.129783 -0.0194013 -0.0100633 0.121749 +EDGE3 508 509 -0.37063 9.41235 0.0314632 -0.0236581 -0.0093092 0.053082 +EDGE3 509 510 -0.317881 9.41413 -0.123953 -0.0258931 -0.0199813 0.102382 +EDGE3 510 511 -0.35013 9.48594 0.0113874 -0.0220122 -0.068619 0.0979869 +EDGE3 511 512 -0.64268 9.22251 -0.018341 -0.0330827 -0.00272866 0.117717 +EDGE3 512 513 -0.494166 9.35387 -0.061975 0.0244273 -0.0339078 0.142557 +EDGE3 513 514 -0.563986 9.19402 -0.0929664 -0.0328964 0.0108264 0.134578 +EDGE3 514 515 -0.421108 9.40295 -0.0839779 -0.0191058 -0.0255789 0.101147 +EDGE3 515 516 -0.502986 9.4368 -0.300206 -0.0116004 -0.0259118 0.0963746 +EDGE3 516 517 -0.352716 9.14454 -0.0899693 0.0166243 0.00446938 0.143652 +EDGE3 517 518 -0.426168 9.32154 0.00442749 -0.0510774 -0.0186415 0.113655 +EDGE3 518 519 -0.332113 9.38871 -0.0493224 0.00969522 0.0238789 0.0706846 +EDGE3 519 520 -0.30962 9.26529 -0.0357703 0.0315462 0.0169164 0.108641 +EDGE3 520 521 -0.416562 9.45416 -0.120916 -0.0130777 -0.0227879 0.0981623 +EDGE3 521 522 -0.590017 9.53584 -0.102417 -0.0118831 0.0161194 0.094979 +EDGE3 522 523 -0.448896 9.37788 0.011292 -0.0131154 0.0184698 0.123384 +EDGE3 523 524 -0.395166 9.40029 -0.100971 -0.021769 -0.0208863 0.144898 +EDGE3 524 525 -0.460876 9.42286 0.0237108 0.0396481 -0.00254159 0.130558 +EDGE3 525 526 -0.513207 9.36216 -0.212452 0.0451533 -0.0357377 0.156618 +EDGE3 526 527 -0.524077 9.42056 -0.3499 0.00616626 -0.0270493 0.142572 +EDGE3 527 528 -0.529384 9.54286 -0.0523876 0.0468028 0.0186213 0.0629372 +EDGE3 528 529 -0.529857 9.50906 -0.0782934 -0.00432528 0.0242863 0.133344 +EDGE3 529 530 -0.590688 9.46638 -0.0814354 -0.0206749 -0.0324303 0.120242 +EDGE3 530 531 -0.466574 9.52159 -0.0527169 -0.00496506 0.0359684 0.0937304 +EDGE3 531 532 -0.671514 9.37158 -0.0274986 0.0190377 -0.0597186 0.125043 +EDGE3 532 533 -0.584392 9.40076 0.0906729 0.0222835 0.00311586 0.127285 +EDGE3 533 534 -0.506768 9.37415 -0.111074 -0.0285215 0.0202286 0.167191 +EDGE3 534 535 -0.663299 9.61647 -0.125291 -0.000438631 -0.0309457 0.0773595 +EDGE3 535 536 -0.464902 9.47018 -0.00758329 -0.0319925 0.0334662 0.109773 +EDGE3 536 537 -0.502731 9.71254 -0.0199327 -0.0381572 -0.017015 0.146335 +EDGE3 537 538 -0.537205 9.53955 -0.0344392 -0.00543011 -0.0399408 0.0866508 +EDGE3 538 539 -0.618342 9.61444 -0.0824221 -0.00414043 0.0447278 0.102938 +EDGE3 539 540 -0.562583 9.49411 -0.113767 -0.0288634 0.0262352 0.129955 +EDGE3 540 541 -0.344221 9.50985 -0.152159 0.0225676 -0.00142588 0.141663 +EDGE3 541 542 -0.481969 9.73707 -0.178698 -0.0396246 0.016919 0.110817 +EDGE3 542 543 -0.51686 9.61598 -0.158557 0.00194433 -0.0411607 0.122784 +EDGE3 543 544 -0.575754 9.59928 -0.0997329 -0.00890796 0.014824 0.119639 +EDGE3 544 545 -0.591223 9.58282 0.122702 0.0416951 0.0114928 0.133286 +EDGE3 545 546 -0.702113 9.72486 -0.0349227 -0.0400373 0.0195651 0.145968 +EDGE3 546 547 -0.611933 9.64652 -0.0603332 0.0210497 0.0193649 0.171309 +EDGE3 547 548 -0.459222 9.36974 -0.0804079 -0.0110629 0.0025275 0.144307 +EDGE3 548 549 -0.6803 9.65765 -0.00323615 -0.00963622 0.0158699 0.0924834 +EDGE3 549 550 -0.341837 9.66781 -0.163417 0.0205601 -0.0306335 0.116093 +EDGE3 550 551 -0.611013 9.68684 -0.0499366 -0.0304591 -0.0373063 0.0969126 +EDGE3 551 552 -0.553838 9.69608 -0.1345 0.0651477 0.0454051 0.0724827 +EDGE3 552 553 -0.467236 9.76765 -0.0899421 -0.015889 -0.0324208 0.151207 +EDGE3 553 554 -0.509782 9.61949 -0.0865762 -0.0157573 -0.0319506 0.133654 +EDGE3 554 555 -0.458336 9.95321 -0.238727 -0.00229506 0.00987974 0.117784 +EDGE3 555 556 -0.623492 9.69664 -0.190644 -0.000436359 -0.013997 0.137374 +EDGE3 556 557 -0.43388 9.52128 -0.0704121 -0.00662889 0.0685089 0.106466 +EDGE3 557 558 -0.449489 9.7938 -0.231752 -0.0050126 -0.0363099 0.117696 +EDGE3 558 559 -0.591202 9.90393 -0.175584 -0.0071838 -0.0172871 0.0943697 +EDGE3 559 560 -0.384864 9.84072 -0.210058 -0.0164692 0.0297865 0.106377 +EDGE3 560 561 -0.345077 9.86296 0.0377365 -0.0132922 -0.00544132 0.175107 +EDGE3 561 562 -0.640874 9.64354 -0.0754047 0.0240544 0.0128955 0.130881 +EDGE3 562 563 -0.583957 9.6882 -0.133283 0.0275744 0.00409077 0.131214 +EDGE3 563 564 -0.759293 9.77637 -0.180837 0.0223968 -0.0467652 0.157285 +EDGE3 564 565 -0.435371 9.92055 -0.0652115 -0.0279807 0.0455928 0.129266 +EDGE3 565 566 -0.504608 10.0585 -0.220355 -0.00423892 -0.0253905 0.154577 +EDGE3 566 567 -0.583105 9.62726 -0.0385599 0.0125931 0.00157288 0.142248 +EDGE3 567 568 -0.418812 9.93973 -0.00904712 0.00424079 -0.025666 0.094345 +EDGE3 568 569 -0.660907 9.80915 0.110031 0.0168833 0.0148951 0.118886 +EDGE3 569 570 -0.580249 9.89147 -0.056416 0.000514778 -0.0310825 0.157983 +EDGE3 570 571 -0.51902 9.77384 -0.0229751 0.0165559 -0.000165297 0.147221 +EDGE3 571 572 -0.65107 9.94078 -0.171718 -0.0762897 -0.0235964 0.0998249 +EDGE3 572 573 -0.546394 9.79195 -0.180318 -0.00559716 0.0168309 0.138522 +EDGE3 573 574 -0.547492 9.80602 -0.0736028 -0.0272302 -0.0282391 0.129652 +EDGE3 574 575 -0.442276 9.99348 -0.0295679 0.00151356 -0.000614518 0.124358 +EDGE3 575 576 -0.669799 10.0336 -0.0869805 0.0201473 -0.0230748 0.125988 +EDGE3 576 577 -0.521559 9.99507 -0.0828248 -0.0150498 -0.00161678 0.11056 +EDGE3 577 578 -0.605875 9.78451 -0.161816 -0.0189688 0.0148465 0.112221 +EDGE3 578 579 -0.606097 9.93736 -0.0481117 0.0312628 0.00137681 0.153689 +EDGE3 579 580 -0.637171 9.98879 -0.28808 0.0301391 -0.0334228 0.0756378 +EDGE3 580 581 -0.500365 9.96867 -0.049431 -0.00215555 0.00976091 0.182599 +EDGE3 581 582 -0.51425 9.90448 -0.208316 -0.0221798 0.0239713 0.10424 +EDGE3 582 583 -0.520655 10.0627 0.0528264 0.0338507 -0.0073872 0.14008 +EDGE3 583 584 -0.728797 10.0483 -0.0995101 -0.0098034 0.00207775 0.138799 +EDGE3 584 585 -0.648124 10.0921 -0.0463311 -0.0175443 0.0507535 0.139984 +EDGE3 585 586 -0.675211 10.0736 0.0223114 -0.0372474 -0.00882792 0.160912 +EDGE3 586 587 -0.503704 9.95501 -0.0267546 -0.00485875 -0.0167479 0.188249 +EDGE3 587 588 -0.411349 10.0697 -0.186202 0.0134565 -0.0227012 0.116589 +EDGE3 588 589 -0.406305 9.98461 -0.0243892 -0.0350094 -0.0208405 0.148564 +EDGE3 589 590 -0.691014 9.95415 -0.189219 0.0348537 -0.00579765 0.151461 +EDGE3 590 591 -0.520553 10.2755 0.109334 0.0239092 -0.037998 0.151086 +EDGE3 591 592 -0.491369 10.1135 -0.0179466 0.00889856 -0.0320038 0.157605 +EDGE3 592 593 -0.492019 10.0383 -0.0382401 -0.00755509 -0.0188169 0.168164 +EDGE3 593 594 -0.449471 10.0017 -0.168103 0.0201938 0.00858649 0.113326 +EDGE3 594 595 -0.729879 10.188 -0.155232 0.0181417 0.00686436 0.14031 +EDGE3 595 596 -0.560451 9.94493 0.0690176 0.000107528 -0.00133283 0.0872198 +EDGE3 596 597 -0.673625 10.1489 0.00164459 -0.00780484 0.025646 0.0614847 +EDGE3 597 598 -0.595394 10.2273 -0.155035 0.0160663 -0.0218437 0.140097 +EDGE3 598 599 -0.495583 10.1149 -0.123623 0.00150941 -0.000877285 0.092582 +EDGE3 599 600 -0.579736 10.2914 -0.135385 -0.00549596 -0.00844412 0.103752 +EDGE3 600 601 -0.35365 10.3 -0.0775417 0.0272434 0.0115904 0.16466 +EDGE3 601 602 -0.565761 10.107 -0.10121 0.00313286 -0.0423423 0.147761 +EDGE3 602 603 -0.593917 10.0805 0.0298388 0.00783662 0.0498798 0.156444 +EDGE3 603 604 -0.88015 10.1421 -0.279469 -0.0378369 -0.0440429 0.128848 +EDGE3 604 605 -0.638044 10.2548 -0.0110429 -0.037602 -0.0662479 0.131769 +EDGE3 605 606 -0.541378 10.1016 -0.128887 0.0236247 0.019471 0.115706 +EDGE3 606 607 -0.692832 10.3356 -0.214519 -0.00562418 -0.0091895 0.117071 +EDGE3 607 608 -0.708266 10.2425 -0.143215 -0.0015925 -0.00778284 0.122099 +EDGE3 608 609 -0.560394 10.3593 -0.0922635 0.0266184 -0.00048235 0.113584 +EDGE3 609 610 -0.549282 10.2762 -0.139436 0.0232315 0.000280683 0.131045 +EDGE3 610 611 -0.444711 10.1474 -0.0863799 -0.0310167 0.0342651 0.146897 +EDGE3 611 612 -0.539971 10.2137 -0.0922161 0.0020689 0.0198164 0.154814 +EDGE3 612 613 -0.428171 10.2533 -0.152533 -8.26767e-05 0.0201169 0.0880881 +EDGE3 613 614 -0.610657 10.2509 -0.0701177 -0.0257348 -0.0523752 0.115455 +EDGE3 614 615 -0.561901 10.302 0.0733974 0.00796174 0.0202938 0.131953 +EDGE3 615 616 -0.604516 10.3608 -0.247837 -0.000144893 0.0309366 0.150894 +EDGE3 616 617 -0.732578 10.4415 -0.0970806 0.0126057 -0.00494759 0.130808 +EDGE3 617 618 -0.632955 10.4202 -0.180957 -0.039366 -0.000601025 0.140456 +EDGE3 618 619 -0.549868 10.3996 0.0239032 0.0155975 -0.0135102 0.145876 +EDGE3 619 620 -0.647024 10.2839 0.0722994 0.0185783 -0.00502041 0.145412 +EDGE3 620 621 -0.588486 10.5196 -0.165451 0.0325856 0.0119994 0.08248 +EDGE3 621 622 -0.503606 10.3338 -0.0450918 -0.00387436 -0.00991225 0.0845384 +EDGE3 622 623 -0.744862 10.4182 -0.0497198 -0.0122801 0.00679071 0.147813 +EDGE3 623 624 -0.590932 10.2843 0.0562619 -0.00200569 0.0261227 0.125755 +EDGE3 624 625 -0.744319 10.2473 -0.130149 -0.00153428 -0.00792725 0.131123 +EDGE3 625 626 -0.505545 10.4701 -0.225927 0.055853 0.00136355 0.123407 +EDGE3 626 627 -0.589711 10.3257 -0.140715 -0.00242569 -0.00648368 0.137392 +EDGE3 627 628 -0.741252 10.2845 -0.122007 0.0416197 -0.0131725 0.141614 +EDGE3 628 629 -0.543724 10.509 -0.0342301 -0.024719 -0.0265984 0.12517 +EDGE3 629 630 -0.474407 10.4362 0.0620068 0.0263064 -0.0185907 0.134034 +EDGE3 630 631 -0.653661 10.4495 -0.127224 -0.0101667 -0.0125662 0.109287 +EDGE3 631 632 -0.541593 10.4344 0.0145756 -0.00610309 0.0240927 0.175733 +EDGE3 632 633 -0.334204 10.3252 -0.172498 -0.00791622 0.0301704 0.0719397 +EDGE3 633 634 -0.401928 10.4628 -0.0759232 0.0507576 -0.0423364 0.128575 +EDGE3 634 635 -0.54982 10.6061 -0.074204 0.0266019 -0.0108024 0.145464 +EDGE3 635 636 -0.523432 10.2874 0.0174404 0.0519617 -0.019657 0.138193 +EDGE3 636 637 -0.516915 10.75 -0.227485 -0.0289954 0.0212853 0.124561 +EDGE3 637 638 -0.937634 10.4344 0.0581246 0.0337455 -0.014629 0.122119 +EDGE3 638 639 -0.48899 10.4637 0.0204038 -0.00265827 -0.0214176 0.119839 +EDGE3 639 640 -0.456639 10.4182 0.00365541 0.0368173 -0.00870094 0.148835 +EDGE3 640 641 -0.498878 10.5087 -0.116529 0.00185414 -0.00704054 0.063953 +EDGE3 641 642 -0.592383 10.4133 -0.0815473 0.0482175 -0.0226021 0.0812033 +EDGE3 642 643 -0.658431 10.5858 -0.151967 -0.00535787 0.0379488 0.162242 +EDGE3 643 644 -0.591201 10.6868 -0.25712 -0.000603227 -0.0138138 0.118098 +EDGE3 644 645 -0.412254 10.5399 -0.217776 0.0410632 -0.0104835 0.157256 +EDGE3 645 646 -0.501536 10.5984 -0.148369 -0.00694208 -0.00959108 0.114519 +EDGE3 646 647 -0.441658 10.6053 -0.225141 -0.0269647 0.0197185 0.163727 +EDGE3 647 648 -0.617436 10.499 0.0300789 0.0496128 -0.00845607 0.12086 +EDGE3 648 649 -0.400338 10.8294 0.0939878 -0.0115074 0.00974918 0.132292 +EDGE3 649 650 -0.494651 10.7357 -0.0217466 0.018297 -0.0295749 0.103268 +EDGE3 650 651 -0.664646 10.5759 -0.207607 -0.0537879 0.0070636 0.132489 +EDGE3 651 652 -0.601087 10.9141 -0.107328 0.0181305 -0.0314801 0.148572 +EDGE3 652 653 -0.74691 10.5242 -0.126424 0.0284586 -0.0120015 0.110807 +EDGE3 653 654 -0.669063 10.6436 -0.0978641 -0.0381515 0.0107075 0.152494 +EDGE3 654 655 -0.790162 10.5872 -0.238857 0.0213422 0.0181164 0.138819 +EDGE3 655 656 -0.380003 10.6851 -0.147754 -0.0155301 -0.00222968 0.142109 +EDGE3 656 657 -0.588139 10.5769 -0.00977376 0.0100096 0.0434776 0.0994393 +EDGE3 657 658 -0.497226 10.8091 -0.0333826 -0.0019529 0.00684735 0.131408 +EDGE3 658 659 -0.654484 10.6906 -0.235507 -0.0102234 -0.040742 0.133663 +EDGE3 659 660 -0.630369 10.6297 -0.00718587 0.0117387 -0.0267532 0.136378 +EDGE3 660 661 -0.392746 10.7911 0.0273434 0.029475 0.0132902 0.136582 +EDGE3 661 662 -0.616919 10.6644 -0.0247015 -0.0340377 0.000319917 0.151231 +EDGE3 662 663 -0.596472 10.7392 0.0878943 0.0141532 0.00273509 0.19548 +EDGE3 663 664 -0.713512 10.7477 -0.0453047 -0.0270619 -0.0227445 0.129743 +EDGE3 665 666 -0.66227 10.7237 -0.225771 -0.00139248 -0.0270882 0.121723 +EDGE3 664 665 -0.768584 10.8786 -0.0541496 0.00653078 0.024345 0.0885954 +EDGE3 666 667 -0.732639 11.0507 -0.24366 -0.00605878 -0.000319506 0.130026 +EDGE3 667 668 -0.485504 10.9053 0.0338068 -0.0810854 0.00712353 0.145792 +EDGE3 668 669 -0.525756 10.6861 -0.150324 0.041852 0.0319852 0.0992715 +EDGE3 669 670 -0.58733 10.7819 -0.0117443 0.0120091 0.0301826 0.111398 +EDGE3 670 671 -0.589293 10.6998 -0.0479086 -0.0136142 -0.0147259 0.151874 +EDGE3 671 672 -0.609871 10.8995 -0.181929 -0.0257439 -0.00325175 0.0890023 +EDGE3 672 673 -0.716451 10.8434 0.0113366 -0.0343243 -0.0594388 0.109766 +EDGE3 673 674 -0.620625 10.67 -0.101183 0.0394398 0.0111823 0.0941084 +EDGE3 674 675 -0.510752 10.9294 -0.107232 0.0137948 -0.00702233 0.0921856 +EDGE3 675 676 -0.82033 10.6322 -0.115144 0.00111414 0.005019 0.118744 +EDGE3 676 677 -0.803215 10.8527 -0.0205366 0.0100041 0.00413699 0.13062 +EDGE3 677 678 -0.534875 10.8963 -0.0478353 0.0195009 0.0250323 0.100169 +EDGE3 678 679 -0.627679 10.9044 0.00515022 -0.0427811 0.0265479 0.126642 +EDGE3 679 680 -0.506963 10.9328 -0.0542087 0.0175667 -0.0129558 0.108869 +EDGE3 680 681 -0.839095 10.7499 -0.0815838 0.0180634 -0.00926397 0.151749 +EDGE3 681 682 -0.594669 10.8893 -0.215995 0.00901051 0.00676044 0.144758 +EDGE3 682 683 -0.52551 10.7654 -0.0631472 0.0334564 -0.020682 0.130264 +EDGE3 683 684 -0.687474 10.8662 0.039089 -0.0488736 -0.0392234 0.174572 +EDGE3 684 685 -0.835656 10.7627 -0.178378 -0.00671276 -0.0111898 0.159491 +EDGE3 685 686 -0.647665 10.8169 -0.209463 -0.00911933 0.0233011 0.0996128 +EDGE3 686 687 -0.616611 10.9003 -0.112664 0.0205933 0.00719554 0.141574 +EDGE3 687 688 -0.530757 10.7944 -0.0126989 -0.0465488 -0.00108581 0.138003 +EDGE3 688 689 -0.752658 10.9632 -0.245523 -0.0211544 0.00242759 0.157612 +EDGE3 689 690 -0.695292 10.8638 -0.0637187 -0.0252215 -0.0101434 0.159737 +EDGE3 690 691 -0.600469 10.9865 0.0600297 0.0165616 0.0592252 0.177891 +EDGE3 691 692 -0.65458 11.2186 -0.150787 0.00163396 0.00471959 0.094319 +EDGE3 692 693 -0.712945 11.007 -0.09499 0.000779006 -0.0399446 0.125397 +EDGE3 693 694 -0.794894 11.0985 -0.235501 0.0242815 0.0172316 0.127108 +EDGE3 694 695 -0.591949 11.088 -0.069569 0.0227117 -0.00291555 0.141675 +EDGE3 695 696 -0.687442 11.2161 -0.196157 -0.0336719 -0.00239286 0.103052 +EDGE3 696 697 -0.815084 10.8452 -0.00495947 -0.00369475 -0.0355957 0.0826594 +EDGE3 697 698 -0.462624 11.0265 -0.133709 -0.00189978 -0.00966264 0.107543 +EDGE3 698 699 -0.521762 10.8635 -0.152054 -0.0225095 -0.00447384 0.122426 +EDGE3 699 700 -0.68687 10.942 -0.0148899 0.0531824 -0.0251391 0.127166 +EDGE3 700 701 -0.562204 11.0006 0.00239 0.00912703 0.0519027 0.144637 +EDGE3 701 702 -0.705836 10.9017 -0.139435 0.0157412 0.0188574 0.123963 +EDGE3 702 703 -0.523375 11.1483 -0.0962653 -0.00851938 0.00374179 0.161846 +EDGE3 703 704 -0.745986 11.0664 -0.123423 0.034364 0.0160229 0.0986006 +EDGE3 704 705 -0.639699 11.0407 -0.12836 0.00964839 0.0272245 0.128389 +EDGE3 705 706 -0.487976 11.0265 -0.0677891 -0.000661507 -0.0498312 0.17019 +EDGE3 706 707 -0.725944 11.0945 -0.181028 0.0249788 0.000549032 0.106139 +EDGE3 707 708 -0.683211 10.9898 0.117685 -0.0282752 0.0315459 0.143414 +EDGE3 708 709 -0.575169 11.1271 -0.0186034 -0.0268973 0.00689893 0.104732 +EDGE3 709 710 -0.559964 10.8057 -0.141654 -0.0384226 -0.0114162 0.103481 +EDGE3 710 711 -0.576749 11.2275 -0.20321 0.00891208 0.0155504 0.110963 +EDGE3 711 712 -0.625349 11.1447 -0.171747 -0.022725 0.0240097 0.121514 +EDGE3 712 713 -0.669889 11.2322 -0.142713 -0.0215008 -0.0132082 0.121461 +EDGE3 713 714 -0.621843 10.9936 -0.0522736 0.0119736 -0.0163135 0.124995 +EDGE3 714 715 -0.599411 11.0718 -0.031367 0.00230053 -0.00178688 0.0973502 +EDGE3 715 716 -0.490987 10.9074 -0.300811 0.0058404 -0.00999171 0.1563 +EDGE3 716 717 -0.573421 11.0741 -0.127133 0.0170648 0.0188859 0.0911173 +EDGE3 717 718 -0.623086 10.9148 -0.104811 -0.00923749 0.022186 0.105062 +EDGE3 718 719 -0.654924 11.0737 -0.0628252 0.00980152 0.0103942 0.151889 +EDGE3 719 720 -0.383911 11.126 -0.0593576 -0.00758614 0.0318917 0.146101 +EDGE3 720 721 -0.686745 11.1537 -0.15888 0.0322838 0.00911944 0.079761 +EDGE3 721 722 -0.723595 10.9838 -0.0266405 0.0193496 0.041608 0.125644 +EDGE3 722 723 -0.569306 11.3456 -0.064007 0.041307 -0.0214223 0.113298 +EDGE3 723 724 -0.62814 11.1692 -0.103583 0.0207471 -0.0251809 0.110041 +EDGE3 724 725 -0.68316 11.0803 -0.159238 0.027791 0.0191503 0.135797 +EDGE3 725 726 -0.623816 10.9559 -0.0735625 0.0357481 0.0340893 0.126012 +EDGE3 726 727 -0.640317 11.2773 0.0414476 0.00722929 -0.00844479 0.0454878 +EDGE3 727 728 -0.662705 11.2037 -0.192275 -0.0117891 -0.0116422 0.135117 +EDGE3 729 730 -0.629166 11.254 -0.00967143 0.0167398 0.0275291 0.169343 +EDGE3 728 729 -0.747785 11.3066 -0.0776214 0.0130414 0.0142884 0.122937 +EDGE3 731 732 -0.645297 11.2255 -0.105746 -0.0375322 0.00904361 0.109279 +EDGE3 730 731 -0.591718 11.1375 -0.113566 0.00986028 -0.00441137 0.0672201 +EDGE3 733 734 -0.627899 11.2116 -0.0810211 -0.0448976 -0.0295828 0.0968198 +EDGE3 732 733 -0.786294 11.3323 -0.212644 -0.0415294 0.0194585 0.143641 +EDGE3 735 736 -0.632089 11.304 -0.0768134 0.00424355 -0.0696194 0.118225 +EDGE3 734 735 -0.673566 11.2043 -0.127292 0.0138337 -0.0244379 0.119011 +EDGE3 737 738 -0.713155 11.3351 -0.0724339 0.00934276 0.00759895 0.119831 +EDGE3 736 737 -0.673207 11.2067 -0.136162 0.010352 0.000784984 0.123193 +EDGE3 739 740 -0.640923 11.1974 -0.158405 0.00979466 -0.0498866 0.10765 +EDGE3 738 739 -0.569882 11.1028 -0.0435145 0.0149744 0.035056 0.109788 +EDGE3 741 742 -0.708584 11.2493 -0.121609 -0.0134295 -0.0426803 0.172525 +EDGE3 740 741 -0.740787 11.2632 -0.138114 0.00650163 -0.0146527 0.0765449 +EDGE3 743 744 -0.491888 11.2774 -0.0353431 -0.00387397 0.0131329 0.156673 +EDGE3 742 743 -0.641856 11.2807 0.0274325 0.0158226 0.0531381 0.0924723 +EDGE3 745 746 -0.808268 11.1206 -0.0483386 -0.0122947 -0.00389021 0.134917 +EDGE3 744 745 -0.771917 11.2746 -0.196096 0.0544498 0.010539 0.114427 +EDGE3 747 748 -0.586487 11.2847 -0.102844 0.0219995 0.0074276 0.155189 +EDGE3 746 747 -0.669507 11.1769 -0.0452237 0.02907 -0.0278881 0.119061 +EDGE3 749 750 -0.858715 11.4476 -0.0213388 -0.0624871 -0.00103245 0.0862353 +EDGE3 748 749 -0.641533 11.3025 -0.00871579 0.0427654 0.029676 0.122719 +EDGE3 750 751 -0.649309 11.2636 -0.147157 0.0352236 -0.00799235 0.138275 +EDGE3 751 752 -0.869942 11.2278 -0.0720114 -0.0473905 0.0050812 0.132713 +EDGE3 752 753 -0.823801 11.1947 -0.168883 0.0407627 -0.0125927 0.121908 +EDGE3 753 754 -0.738987 11.3756 -0.359176 0.00389317 0.0148241 0.15601 +EDGE3 754 755 -0.761464 11.3628 -0.117523 0.00101623 0.00661009 0.119072 +EDGE3 755 756 -0.62733 11.4863 -0.179828 0.0144695 -0.0339339 0.142466 +EDGE3 756 757 -0.759613 11.2009 -0.3027 -0.00153063 -0.0182157 0.172399 +EDGE3 757 758 -0.753795 11.5658 -0.186494 -0.00478204 0.0381412 0.127497 +EDGE3 758 759 -0.716432 11.5854 0.019814 0.0215565 -0.0156851 0.0878506 +EDGE3 759 760 -0.857631 11.3725 -0.324034 -0.0286909 -0.0072389 0.115925 +EDGE3 760 761 -0.564986 11.2901 -0.168735 0.0335559 0.0132867 0.1178 +EDGE3 761 762 -0.624602 11.4161 -0.103096 -0.0742735 0.00547345 0.0966695 +EDGE3 762 763 -0.730441 11.325 -0.00859699 0.0289852 -0.0404061 0.0980436 +EDGE3 763 764 -0.623399 11.4052 -0.0405101 0.0166184 0.00422661 0.131983 +EDGE3 764 765 -0.751135 11.345 -0.245395 -0.0296714 0.0247943 0.126582 +EDGE3 765 766 -0.456256 11.4209 -0.217299 -0.0359357 0.0155084 0.152613 +EDGE3 766 767 -0.497603 11.2884 -0.223088 -0.0168023 0.0492511 0.0955121 +EDGE3 767 768 -0.607295 11.3577 -0.0242014 -0.0407421 -0.0188519 0.120699 +EDGE3 768 769 -0.762157 11.3324 -0.23283 0.0123768 -0.0166862 0.121811 +EDGE3 769 770 -0.63583 11.5181 -0.057269 -0.0191341 0.00461432 0.131446 +EDGE3 770 771 -0.733513 11.5643 -0.0645911 0.00383694 -0.0056335 0.128574 +EDGE3 771 772 -0.702886 11.4133 -0.148503 0.0164051 0.0149995 0.0691098 +EDGE3 772 773 -0.670083 11.3915 -0.0944627 0.00714223 -0.00596539 0.114582 +EDGE3 773 774 -0.553672 11.4808 -0.348721 0.0175321 -0.0313712 0.11777 +EDGE3 774 775 -0.819521 11.3265 -0.100717 -0.0317067 -0.0039908 0.119591 +EDGE3 775 776 -0.605185 11.5203 0.0535101 0.0384817 -0.0161191 0.131636 +EDGE3 776 777 -0.489229 11.498 0.046753 -0.0289639 0.00439944 0.144558 +EDGE3 777 778 -0.662014 11.472 -0.0895961 0.0100766 -0.0116892 0.110842 +EDGE3 778 779 -0.593485 11.4806 0.0292226 -0.0272418 -0.00739642 0.122532 +EDGE3 779 780 -0.613724 11.5799 -0.0421083 0.0298456 0.00144193 0.144726 +EDGE3 780 781 -0.522931 11.4698 -0.157904 -0.0302536 0.00087618 0.123218 +EDGE3 781 782 -0.868297 11.5272 -0.0100059 0.0187538 0.0195099 0.145113 +EDGE3 782 783 -0.693848 11.6522 -0.285085 0.00727625 -0.0111887 0.0864028 +EDGE3 783 784 -0.730065 11.4833 0.0680907 0.00525073 0.00946078 0.100429 +EDGE3 784 785 -0.694131 11.4139 -0.123119 0.00201867 0.0348285 0.141161 +EDGE3 785 786 -0.613879 11.5545 -0.106061 -0.0305967 0.00378237 0.0648066 +EDGE3 786 787 -0.550279 11.5459 -0.227432 0.0130018 0.0160446 0.111967 +EDGE3 787 788 -0.57525 11.7817 0.0237502 0.00553513 0.00328994 0.138892 +EDGE3 788 789 -0.770584 11.5206 0.0433127 -0.013363 0.00848641 0.0891157 +EDGE3 789 790 -0.622863 11.7297 -0.0711459 -0.0123988 0.0605069 0.163007 +EDGE3 790 791 -0.510269 11.5654 -0.168263 0.0224371 -0.0110497 0.135575 +EDGE3 791 792 -0.682655 11.4946 -0.0998997 0.00257173 0.0397944 0.151197 +EDGE3 792 793 -0.730061 11.5514 -0.142537 -0.0199822 -0.0277997 0.116125 +EDGE3 793 794 -0.60549 11.5649 -0.0159346 0.0210973 -0.0177114 0.145375 +EDGE3 794 795 -0.815238 11.554 -0.14138 -0.0223306 -0.0363467 0.102426 +EDGE3 795 796 -0.633403 11.5727 -0.256176 0.001124 -0.0134933 0.138225 +EDGE3 796 797 -0.786517 11.5877 -0.178135 -0.0250794 0.0194774 0.0654389 +EDGE3 797 798 -0.719277 11.662 -0.243779 0.0171121 0.0156303 0.176665 +EDGE3 798 799 -0.685454 11.6387 0.063688 0.00513375 0.00388497 0.109556 +EDGE3 799 800 -0.589601 11.7057 -0.0918285 0.00323494 -0.00905249 0.11474 +EDGE3 800 801 -0.616668 11.6399 -0.127585 0.0208997 -0.0428943 0.0698618 +EDGE3 801 802 -0.750759 11.647 0.00527676 -0.0314129 0.0381739 0.14109 +EDGE3 802 803 -0.689934 11.6104 -0.144727 -0.00691586 0.0110097 0.138723 +EDGE3 803 804 -0.654329 11.6807 -0.299351 -0.016207 -0.0130176 0.0922021 +EDGE3 804 805 -0.71325 11.6174 -0.247185 -0.0131055 0.0231408 0.136037 +EDGE3 805 806 -0.831539 11.819 -0.156321 0.0211648 0.0185782 0.0956072 +EDGE3 806 807 -0.665039 11.6899 -0.165244 -0.017346 0.00670423 0.122658 +EDGE3 807 808 -0.826803 11.6651 -0.206612 0.00154575 0.0194254 0.156979 +EDGE3 808 809 -0.585279 11.7909 -0.134395 -0.0386023 0.00198799 0.152156 +EDGE3 809 810 -0.898298 11.7763 -0.192646 0.00389181 -0.0210774 0.0670251 +EDGE3 810 811 -0.75429 11.7916 -0.237213 -0.0461283 0.0074222 0.0927254 +EDGE3 811 812 -0.663224 11.6124 -0.189041 -0.00123376 0.0101671 0.164593 +EDGE3 812 813 -0.765255 11.74 -0.151041 0.00504807 -0.00635209 0.124817 +EDGE3 813 814 -0.632111 11.5904 -0.282287 -0.0592282 -0.0223453 0.136917 +EDGE3 814 815 -0.702276 11.5611 0.111001 -0.0146572 -0.0297494 0.17961 +EDGE3 815 816 -0.633299 11.7893 -0.156848 0.00196402 -0.0368688 0.109714 +EDGE3 816 817 -0.590886 11.7373 -0.233355 0.0101475 -0.00730159 0.13714 +EDGE3 817 818 -0.667103 11.8448 -0.227906 -0.0241993 0.0195925 0.0947878 +EDGE3 818 819 -0.739056 11.6907 -0.266086 0.0166344 0.017775 0.114675 +EDGE3 819 820 -0.753734 11.7017 -0.100248 -0.00763366 -0.0038417 0.194878 +EDGE3 820 821 -0.680164 11.7826 -0.184943 -0.000873303 0.00507169 0.105098 +EDGE3 821 822 -0.632523 11.5689 -0.0588963 -0.000657909 0.0192009 0.107669 +EDGE3 822 823 -0.717916 11.7235 -0.238238 -0.00867143 -0.0152566 0.121073 +EDGE3 823 824 -0.857452 11.6628 -0.0859608 -0.00366124 0.0357554 0.108158 +EDGE3 824 825 -0.789681 11.7622 -0.217677 0.0041665 -0.00385137 0.12833 +EDGE3 825 826 -0.792671 11.6024 -0.243491 -0.017026 0.0360949 0.123282 +EDGE3 826 827 -0.58394 11.6733 -0.13811 -0.0206171 -0.018804 0.0939978 +EDGE3 827 828 -0.789333 11.8553 -0.141847 0.030524 -0.00959597 0.137998 +EDGE3 828 829 -0.539641 11.8278 -0.0101806 -0.0303427 0.0334132 0.11254 +EDGE3 829 830 -0.617863 12.0277 -0.0706224 0.0226627 0.000919939 0.131682 +EDGE3 830 831 -0.670354 11.8194 -0.0832365 -0.0246532 -0.0109335 0.142523 +EDGE3 831 832 -0.698097 11.8348 -0.162876 0.0291299 -0.00230172 0.157775 +EDGE3 832 833 -0.829211 11.9336 -0.117647 0.0396994 -0.0250838 0.0992035 +EDGE3 833 834 -0.691895 11.9213 0.0318949 0.0170468 -0.0134209 0.139691 +EDGE3 834 835 -0.455491 11.8175 -0.272552 -0.00763231 -0.00397073 0.112506 +EDGE3 835 836 -0.539987 11.872 -0.0826496 -0.0134346 -0.033923 0.130991 +EDGE3 836 837 -0.760323 11.847 -0.196677 -0.0029314 0.0136777 0.104547 +EDGE3 837 838 -0.843612 11.7159 -0.187819 0.0271338 0.0197938 0.100072 +EDGE3 838 839 -0.615614 11.761 -0.0664561 -0.0161247 0.00179751 0.156159 +EDGE3 839 840 -0.810274 11.8291 -0.0109603 0.0431663 -0.032561 0.0883044 +EDGE3 840 841 -0.832701 12.0225 -0.0440459 -0.00858529 -0.0272606 0.127188 +EDGE3 841 842 -0.712871 11.9951 -0.240134 -0.00693222 0.0026366 0.122756 +EDGE3 842 843 -0.77068 11.9913 -0.153277 0.0317926 -0.0394176 0.160023 +EDGE3 843 844 -0.690626 12.1066 -0.031988 0.0153329 0.00237161 0.147308 +EDGE3 844 845 -0.771342 11.7605 -0.0798066 0.00314307 0.0282584 0.158631 +EDGE3 845 846 -0.804645 11.8315 -0.20449 -0.0093038 0.0136013 0.106236 +EDGE3 846 847 -0.736638 12.0176 -0.0281956 -0.0840391 0.0289455 0.0904216 +EDGE3 847 848 -0.459807 11.9297 -0.321135 -0.0628447 0.0310872 0.1199 +EDGE3 848 849 -0.699828 11.8898 -0.0758647 0.0172072 0.00796348 0.120963 +EDGE3 849 850 -0.717524 12.0151 -0.00356581 -0.0076972 -0.0510018 0.13303 +EDGE3 850 851 -0.734513 11.7539 -0.126567 0.00835793 -0.018566 0.135551 +EDGE3 851 852 -0.57587 11.8564 -0.0115039 0.0108649 -0.0149321 0.145063 +EDGE3 852 853 -0.771243 11.9346 -0.238415 0.00423455 0.000355828 0.0916853 +EDGE3 853 854 -0.773857 11.9675 -0.0771789 -0.0354557 -0.00573538 0.121763 +EDGE3 854 855 -0.799955 12.0126 0.0232991 -0.00340641 -0.0132741 0.11525 +EDGE3 855 856 -0.72757 11.9195 -0.0294622 -0.0287391 -0.00519506 0.179788 +EDGE3 856 857 -0.557111 11.945 -0.207288 -0.0449343 -0.050059 0.129505 +EDGE3 857 858 -0.586848 12.1391 -0.150817 -0.016757 0.000806583 0.119582 +EDGE3 858 859 -0.756425 11.972 -0.0591718 0.00608936 0.00319501 0.103747 +EDGE3 859 860 -0.739117 12.1288 -0.038381 -0.0156557 0.0153042 0.117149 +EDGE3 860 861 -0.715078 11.8469 -0.0344951 -0.0128342 0.00266633 0.120967 +EDGE3 861 862 -0.732168 12.2183 -0.0625808 0.00437515 0.0270384 0.143665 +EDGE3 862 863 -0.645136 11.9812 -0.155359 -0.00264511 -0.00441136 0.123699 +EDGE3 863 864 -0.894341 11.884 -0.103596 0.0343545 0.0356571 0.11499 +EDGE3 864 865 -0.810778 11.94 -0.0442439 0.00117971 0.00552553 0.154264 +EDGE3 865 866 -0.654913 12.0156 -0.296066 -0.0329312 0.0282763 0.109329 +EDGE3 866 867 -0.659943 11.9182 -0.11817 -0.0116617 -0.00322966 0.0813899 +EDGE3 867 868 -0.577719 12.0034 -0.142515 -0.0459935 0.0127893 0.104513 +EDGE3 868 869 -0.783146 11.9312 0.0170831 -0.0197049 -0.000868907 0.144051 +EDGE3 869 870 -0.997622 11.8427 -0.140152 -0.0200887 -0.00538 0.131414 +EDGE3 870 871 -0.62283 11.9317 -0.0221585 0.0131853 0.0267817 0.106995 +EDGE3 871 872 -0.834861 12.0936 -0.0430666 -0.00969133 -0.0196581 0.106678 +EDGE3 872 873 -0.767198 12.0252 -0.00618724 -0.00733851 -0.0261495 0.0899095 +EDGE3 873 874 -0.641691 12.0225 -0.0202817 -0.0217425 0.000286311 0.141538 +EDGE3 874 875 -0.693478 12.0514 -0.0528624 -0.0240539 -0.0562632 0.14046 +EDGE3 875 876 -0.750347 11.9617 -0.0686156 -0.0213461 -0.0238533 0.123387 +EDGE3 876 877 -0.782156 12.1556 0.103009 0.0467122 0.00485887 0.137216 +EDGE3 877 878 -0.739106 12.0054 0.096128 0.0435807 0.00647681 0.0929089 +EDGE3 878 879 -0.567285 11.9689 -0.177967 -0.0244536 -0.0298197 0.112014 +EDGE3 879 880 -0.559373 12.0689 -0.0868761 0.0272594 0.0111953 0.116944 +EDGE3 880 881 -0.58923 11.9119 -0.203776 0.0191678 -0.00800863 0.13014 +EDGE3 881 882 -0.723155 12.0635 -0.112818 0.00700565 -0.0375723 0.154246 +EDGE3 882 883 -0.656861 12.152 0.00750553 0.00303905 -0.00254118 0.158492 +EDGE3 883 884 -0.778584 12.3151 -0.124851 -0.00716528 0.0210182 0.123722 +EDGE3 884 885 -0.886622 12.0711 -0.046487 -0.00714683 -0.0152155 0.0860002 +EDGE3 885 886 -0.774558 12.1531 -0.13755 -0.00730911 0.0256613 0.159071 +EDGE3 886 887 -0.646913 11.9812 -0.0578245 0.0220106 0.0453262 0.130622 +EDGE3 887 888 -0.862665 12.0598 -0.134801 -0.0102033 -0.0108392 0.13163 +EDGE3 888 889 -0.825993 12.0537 -0.0475197 0.0637299 -0.0171945 0.141465 +EDGE3 889 890 -0.783528 11.9474 -0.0401985 -0.00697926 -0.0167632 0.0827948 +EDGE3 890 891 -0.72636 12.1457 -0.172064 0.00786199 -0.0180467 0.110721 +EDGE3 891 892 -0.636433 12.2437 -0.0113698 -0.00619282 -0.0650527 0.0988323 +EDGE3 892 893 -0.883243 12.0078 -0.0537395 -0.00394482 -0.0407889 0.123224 +EDGE3 893 894 -0.741357 12.3913 -0.0770973 -0.00372312 0.0160375 0.10736 +EDGE3 894 895 -0.784783 12.0805 -0.140978 -0.0301552 0.0109459 0.149605 +EDGE3 895 896 -0.677119 12.1097 -0.194749 -0.0362648 -0.0419967 0.163679 +EDGE3 896 897 -0.686436 12.1398 -0.275661 -0.004902 0.00397047 0.197478 +EDGE3 897 898 -0.716522 12.2355 -0.0700259 -0.0691566 0.0386549 0.0954966 +EDGE3 898 899 -0.780579 11.951 -0.0563514 -0.00401373 0.0275071 0.149314 +EDGE3 899 900 -0.684515 12.2782 -0.0329125 -0.00990015 0.0264426 0.104344 +EDGE3 900 901 -0.810444 12.2319 -0.0659277 -0.000169738 -0.00983914 0.17002 +EDGE3 901 902 -0.815265 12.2327 -0.177169 -0.0204132 0.0105872 0.118563 +EDGE3 902 903 -0.812253 12.2449 -0.0819598 -0.0509856 -0.0268032 0.125356 +EDGE3 903 904 -0.835369 12.1473 -0.0695565 0.0253345 0.0152324 0.144658 +EDGE3 904 905 -0.723494 12.2123 -0.316082 -0.0280839 -0.019402 0.109898 +EDGE3 905 906 -0.68831 11.9487 0.000435407 0.030422 -0.0157061 0.11782 +EDGE3 906 907 -0.696601 12.1307 -0.190448 0.0481673 0.00260072 0.125452 +EDGE3 907 908 -0.680013 12.1329 -0.337967 0.0311842 0.0425776 0.151644 +EDGE3 908 909 -0.784191 12.1762 -0.195542 -0.0334178 0.00566662 0.133343 +EDGE3 909 910 -0.848076 12.0579 -0.297072 -0.0152558 0.0290907 0.105801 +EDGE3 910 911 -0.556112 12.104 -0.123092 0.00755576 -0.013093 0.0983882 +EDGE3 911 912 -0.835501 12.1023 0.0148817 -0.00697699 0.020446 0.105861 +EDGE3 912 913 -0.544022 12.2493 -0.0566269 0.00073424 -0.030655 0.11402 +EDGE3 913 914 -0.775706 12.1821 -0.253796 -0.0383812 -0.0240629 0.173704 +EDGE3 914 915 -0.772151 12.0979 -0.128805 0.0306251 -0.00822216 0.143357 +EDGE3 915 916 -0.726597 12.2193 -0.143278 0.0116003 0.0642104 0.123343 +EDGE3 916 917 -0.531344 12.2871 -0.234532 -0.0143685 -0.019085 0.158591 +EDGE3 917 918 -0.632429 12.3343 -0.150348 -0.00829013 -0.0186821 0.0991102 +EDGE3 918 919 -0.736976 12.3324 -0.253539 0.0666724 -0.0131432 0.112259 +EDGE3 919 920 -0.806298 12.1291 -0.104578 -0.00133974 0.0234099 0.093851 +EDGE3 920 921 -0.755241 12.273 -0.203616 0.0203431 0.00211243 0.156837 +EDGE3 921 922 -0.74127 12.2971 -0.0118481 0.0193089 -0.0253733 0.12345 +EDGE3 922 923 -0.792226 12.2143 -0.177647 -0.0174911 -0.0367932 0.168977 +EDGE3 923 924 -0.760733 12.1451 -0.267815 -0.015081 0.000973712 0.157705 +EDGE3 924 925 -0.770571 12.3439 -0.298049 -0.027788 0.00497538 0.119392 +EDGE3 925 926 -0.831669 12.2765 -0.0114447 0.0381671 -0.0053206 0.157376 +EDGE3 926 927 -0.866158 12.2497 -0.284571 0.0357926 -0.02924 0.161034 +EDGE3 927 928 -0.709464 12.3084 -0.173047 -0.0296195 -0.021156 0.125486 +EDGE3 928 929 -0.797004 12.3717 -0.0325491 -0.018157 0.017341 0.117049 +EDGE3 929 930 -0.631737 12.2908 -0.0362696 -0.010444 -0.00359219 0.155562 +EDGE3 930 931 -0.867702 12.3322 -0.116586 0.0423811 0.0229631 0.166948 +EDGE3 931 932 -0.772188 12.2295 -0.125337 0.01155 -0.0111061 0.12044 +EDGE3 932 933 -0.701517 12.2167 -0.0948382 0.0214928 0.0160242 0.0805813 +EDGE3 933 934 -0.671083 12.3393 -0.105229 0.0251512 -0.0197197 0.122603 +EDGE3 935 936 -0.768807 12.453 -0.0211649 0.00120655 0.00290915 0.0852832 +EDGE3 934 935 -0.932697 12.1915 -0.0483363 -0.0494348 0.0208588 0.130589 +EDGE3 937 938 -0.818838 12.2557 -0.0260403 -0.00692361 0.0331361 0.164103 +EDGE3 936 937 -0.817335 12.3918 -0.0764988 -0.0206066 0.0150018 0.0865452 +EDGE3 939 940 -0.902114 12.0891 -0.155462 -0.0341703 -0.00101813 0.115427 +EDGE3 938 939 -0.695052 12.2774 -0.158173 0.00232756 0.00429144 0.131076 +EDGE3 941 942 -0.605786 12.3235 -0.0211012 -0.0137308 0.00134488 0.142249 +EDGE3 940 941 -0.624621 12.3004 -0.16873 0.0135855 0.0239019 0.138063 +EDGE3 943 944 -0.618929 12.4169 -0.00908552 0.0276399 -0.00873477 0.117642 +EDGE3 942 943 -0.512801 12.2296 0.015682 0.00197144 0.0272809 0.109174 +EDGE3 945 946 -0.784871 12.3572 -0.188394 -0.00599221 -0.0144124 0.103471 +EDGE3 944 945 -0.795445 12.1095 -0.0678067 0.00542462 0.00230227 0.125306 +EDGE3 947 948 -0.827982 12.2142 -0.212925 0.00119153 0.025298 0.150139 +EDGE3 946 947 -0.652731 12.1527 -0.408477 -0.00622862 0.00935509 0.135019 +EDGE3 949 950 -0.854788 11.9969 -0.198278 0.00673434 0.036451 0.128129 +EDGE3 948 949 -0.716527 12.3319 -0.226126 0.028264 0.0651313 0.130979 +EDGE3 951 952 -0.68031 12.3753 -0.0154732 -0.0284807 -0.000782939 0.117897 +EDGE3 950 951 -0.760208 12.2798 -0.0851598 0.0606329 -0.0264887 0.0926776 +EDGE3 953 954 -0.82016 12.2662 -0.165759 -0.0100074 0.00548445 0.127921 +EDGE3 952 953 -0.857142 12.2694 -0.0366153 -0.0207386 0.0151242 0.148294 +EDGE3 955 956 -0.730325 12.1761 -0.215835 -0.00796853 -0.0100465 0.0944207 +EDGE3 954 955 -1.06855 12.414 -0.0159135 0.00741257 -0.0112472 0.138041 +EDGE3 957 958 -0.924797 12.3325 -0.29464 -0.0200971 -0.0163561 0.133858 +EDGE3 956 957 -0.840251 12.2534 -0.0605857 -0.0166428 0.0292487 0.100407 +EDGE3 959 960 -0.673839 12.3522 -0.0540179 -0.00368146 -0.00642344 0.149871 +EDGE3 958 959 -0.890572 12.3049 -0.0738878 0.0148263 0.00141786 0.149776 +EDGE3 961 962 -0.743323 12.5171 -0.255888 -0.0116075 0.00824523 0.184157 +EDGE3 960 961 -0.668838 12.3246 -0.187756 -0.0135488 0.0553892 0.144504 +EDGE3 963 964 -0.879538 12.4358 -0.142695 -0.0102119 -0.0258646 0.152962 +EDGE3 962 963 -0.621808 12.4563 -0.162884 -0.016232 -0.0127233 0.134937 +EDGE3 965 966 -0.89436 12.4375 -0.194219 -0.0421899 0.00207009 0.104813 +EDGE3 964 965 -0.837207 12.4484 -0.259812 -0.0395812 0.00677228 0.112721 +EDGE3 967 968 -0.831167 12.212 -0.203825 -0.00886314 -0.0290924 0.146539 +EDGE3 966 967 -0.743807 12.396 0.0171032 0.00436761 0.0428979 0.125092 +EDGE3 969 970 -0.882147 12.3404 -0.195925 0.0106351 0.0184583 0.150728 +EDGE3 968 969 -0.749005 12.3064 -0.0786516 -0.0279086 0.0196705 0.16171 +EDGE3 971 972 -0.593741 12.3109 -0.245133 0.00114195 -0.022784 0.127932 +EDGE3 970 971 -0.728467 12.4067 -0.037172 -0.0086391 0.0153284 0.13324 +EDGE3 973 974 -0.799276 12.3987 -0.069661 0.0313798 0.0142803 0.13439 +EDGE3 972 973 -0.899244 12.425 -0.13861 0.0131767 -0.0158468 0.119804 +EDGE3 975 976 -0.55343 12.5124 -0.209114 -0.0307383 0.0530055 0.12917 +EDGE3 974 975 -0.795531 12.5232 -0.11732 -0.0208296 0.0119754 0.14353 +EDGE3 977 978 -0.753021 12.2499 -0.152241 0.0260755 -0.0382892 0.176485 +EDGE3 976 977 -0.764614 12.5324 -0.00413744 -0.0129302 -0.00597653 0.136102 +EDGE3 979 980 -0.850845 12.4883 -0.139722 -0.0331608 -0.021345 0.129172 +EDGE3 978 979 -0.739118 12.2633 0.0275688 0.0318407 0.0150229 0.10233 +EDGE3 981 982 -0.953901 12.277 -0.308221 -0.00881291 0.012377 0.115896 +EDGE3 980 981 -0.771884 12.3306 -0.185693 -0.0125218 -0.0282315 0.14249 +EDGE3 983 984 -0.654837 12.2968 -0.247198 -0.0563104 -0.0243699 0.119513 +EDGE3 982 983 -0.777138 12.4338 -0.223396 -0.000681145 0.011324 0.127693 +EDGE3 985 986 -0.8113 12.5012 0.0576306 0.0134755 -0.0322337 0.132422 +EDGE3 984 985 -0.919598 12.4127 -0.254859 -0.00603206 0.0171533 0.172918 +EDGE3 987 988 -0.773409 12.2891 -0.0260586 0.0414523 0.00656872 0.0896918 +EDGE3 986 987 -0.740969 12.433 0.00683932 -0.0326555 0.0222159 0.134067 +EDGE3 989 990 -0.741325 12.3486 -0.144608 -0.0127338 0.0299149 0.12895 +EDGE3 988 989 -0.813187 12.4354 -0.0684864 -0.0188532 0.0443436 0.137879 +EDGE3 991 992 -0.806567 12.4337 -0.190982 0.0234849 0.0199472 0.087183 +EDGE3 990 991 -0.776819 12.3899 -0.162899 -0.00240002 0.0110967 0.133645 +EDGE3 993 994 -0.777737 12.558 -0.0168142 -0.0194726 0.0542417 0.109253 +EDGE3 992 993 -0.691569 12.3834 -0.312581 -0.00681118 0.0229237 0.0842752 +EDGE3 995 996 -0.713526 12.3547 -0.159192 0.0486005 0.0327949 0.0958806 +EDGE3 994 995 -0.753184 12.5707 -0.133179 -0.0152624 -0.00779516 0.150971 +EDGE3 997 998 -0.609292 12.432 -0.119188 0.0248267 0.0168224 0.13237 +EDGE3 996 997 -0.638763 12.4736 -0.283511 0.0548062 -0.0220283 0.170199 +EDGE3 998 999 -0.94129 12.621 -0.123122 -0.0231088 0.0101881 0.112475 +EDGE3 999 1000 -0.770355 12.5119 -0.0112162 -0.00362324 -0.00765399 0.149456 +EDGE3 1001 1002 -0.818004 12.3718 -0.0739948 0.0350102 0.0213367 0.139486 +EDGE3 1000 1001 -0.754289 12.4218 -0.0235324 -0.0143865 0.014946 0.133153 +EDGE3 1003 1004 -0.628151 12.7001 0.099821 -0.0544134 -0.0188109 0.111529 +EDGE3 1002 1003 -0.780939 12.4841 -0.222558 -0.0186912 -0.0265403 0.153187 +EDGE3 1005 1006 -0.685569 12.4991 -0.17753 0.014353 0.0213487 0.157336 +EDGE3 1004 1005 -0.774782 12.361 -0.123567 0.0136591 0.00500777 0.137322 +EDGE3 1007 1008 -0.678872 12.4765 -0.101926 0.0208593 0.00682785 0.150527 +EDGE3 1006 1007 -0.855423 12.4642 -0.155348 -0.0127244 0.0221665 0.117101 +EDGE3 1009 1010 -0.792503 12.4501 -0.230941 0.057893 0.00381654 0.111096 +EDGE3 1008 1009 -0.752591 12.2735 -0.231635 0.000390032 0.0287599 0.142325 +EDGE3 1011 1012 -0.767666 12.462 -0.210168 0.0308723 -0.0720105 0.0978262 +EDGE3 1010 1011 -0.686065 12.5991 -0.110267 0.00147787 0.0210146 0.159407 +EDGE3 1013 1014 -0.776654 12.5145 -0.0180128 0.0183683 0.0180729 0.0909042 +EDGE3 1012 1013 -0.72987 12.498 -0.455596 0.0550661 -0.0342372 0.101391 +EDGE3 1015 1016 -0.801317 12.334 -0.0574876 0.00245043 0.0240828 0.141272 +EDGE3 1014 1015 -0.653216 12.6133 -0.119983 -0.0098045 0.0182495 0.118618 +EDGE3 1017 1018 -0.730502 12.3266 -0.041379 0.0397401 0.00331037 0.122346 +EDGE3 1016 1017 -0.662213 12.5072 -0.192535 -0.0309323 -0.0439541 0.177429 +EDGE3 1019 1020 -0.79374 12.4242 -0.184693 -0.00955902 -0.00038612 0.1024 +EDGE3 1018 1019 -0.745691 12.5231 -0.179064 0.0031453 0.0157125 0.115233 +EDGE3 1021 1022 -0.771216 12.563 -0.21576 0.0177217 0.00799737 0.170896 +EDGE3 1020 1021 -0.822661 12.3176 -0.10949 0.0133385 0.0333913 0.171937 +EDGE3 1023 1024 -0.624188 12.5846 -0.139115 -0.031795 0.0153855 0.0986369 +EDGE3 1022 1023 -0.672843 12.5216 -0.0840654 0.0490084 -0.0248084 0.131441 +EDGE3 1025 1026 -0.908039 12.4056 -0.128283 -0.00035526 -0.00737729 0.154627 +EDGE3 1024 1025 -0.909052 12.363 -0.286727 -0.0169572 -0.000294458 0.103581 +EDGE3 1027 1028 -0.821987 12.6213 -0.126123 -0.00128162 -0.0199038 0.134766 +EDGE3 1026 1027 -0.734965 12.4168 -0.0464078 -0.0130175 -0.0129324 0.183371 +EDGE3 1029 1030 -0.723338 12.4691 -0.191035 -0.0501349 -0.00509426 0.0905996 +EDGE3 1028 1029 -0.889808 12.4777 0.0410057 -0.0371751 -0.0150807 0.118381 +EDGE3 1030 1031 -0.731658 12.6184 -0.208084 -0.0503483 0.00697068 0.0970263 +EDGE3 1031 1032 -0.781821 12.5399 -0.150645 0.01668 -0.0105589 0.0898273 +EDGE3 1032 1033 -0.837034 12.3004 -0.118316 0.0058053 0.0040919 0.0992607 +EDGE3 1033 1034 -0.747228 12.5607 -0.240128 -0.0411953 -0.0193755 0.159705 +EDGE3 1034 1035 -0.815566 12.5947 -0.182688 -0.0194676 0.0296271 0.149699 +EDGE3 1035 1036 -0.693142 12.498 -0.104325 -0.0514158 -0.0140275 0.122265 +EDGE3 1036 1037 -0.762587 12.325 -0.0843814 0.041794 0.0231222 0.130226 +EDGE3 1037 1038 -0.747134 12.4408 -0.0717559 -0.0572477 0.0275566 0.123142 +EDGE3 1038 1039 -0.651832 12.5975 -0.111613 0.0354207 -0.0324765 0.145073 +EDGE3 1039 1040 -0.782276 12.5773 -0.247266 -0.011791 -0.0110472 0.104183 +EDGE3 1040 1041 -0.7945 12.4415 0.00714978 0.0175498 0.012309 0.0891308 +EDGE3 1041 1042 -0.531202 12.3911 -0.111094 -0.0356944 0.0269212 0.117978 +EDGE3 1042 1043 -0.726103 12.3322 -0.0656701 0.00191577 -0.0315541 0.144546 +EDGE3 1043 1044 -0.731681 12.5301 -0.0589063 -0.04129 -0.0366536 0.08393 +EDGE3 1044 1045 -0.882057 12.6495 -0.140599 0.0161681 0.00599155 0.143304 +EDGE3 1045 1046 -0.638213 12.3644 -0.188435 0.00399867 -0.00310412 0.0983785 +EDGE3 1046 1047 -0.605123 12.4468 -0.0798453 0.040033 -0.0539916 0.109847 +EDGE3 1047 1048 -0.890712 12.6131 -0.17422 0.0547023 -0.041738 0.133018 +EDGE3 1048 1049 -0.753494 12.5052 -0.054073 0.00392159 0.0258411 0.11469 +EDGE3 1049 1050 -0.828331 12.5565 -0.047078 -0.00846573 0.0188966 0.143595 +EDGE3 1050 1051 -0.715009 12.4392 -0.10279 0.0250455 -0.00628338 0.107394 +EDGE3 1051 1052 -0.435144 12.5755 -0.252303 -0.0169955 -0.0366715 0.140231 +EDGE3 1052 1053 -0.732725 12.7205 -0.197998 0.0149291 0.00505819 0.108381 +EDGE3 1053 1054 -0.879687 12.4814 -0.155387 0.0234694 0.0228448 0.174477 +EDGE3 1054 1055 -0.785634 12.4901 -0.275353 0.00910175 -0.0214037 0.108947 +EDGE3 1055 1056 -0.728128 12.3562 -0.056325 -0.000285393 0.0250425 0.103778 +EDGE3 1056 1057 -0.69518 12.7271 0.0461303 -0.0216063 0.00920557 0.138244 +EDGE3 1057 1058 -0.631501 12.6392 -0.241629 0.0224738 -0.0468653 0.0983846 +EDGE3 1058 1059 -0.850292 12.6121 -0.192422 -0.0190627 0.0549652 0.0806549 +EDGE3 1059 1060 -0.740747 12.4755 -0.112769 0.003535 0.0491866 0.135885 +EDGE3 1060 1061 -0.740349 12.4733 -0.265983 -0.0220753 -0.00305963 0.13946 +EDGE3 1061 1062 -0.720855 12.618 -0.107745 0.0213858 -0.0169565 0.152976 +EDGE3 1062 1063 -0.590413 12.5931 -0.0986973 -0.0118397 0.0252493 0.106009 +EDGE3 1063 1064 -0.795179 12.3691 -0.0384184 -0.0352546 -0.00972836 0.137016 +EDGE3 1064 1065 -0.686523 12.4968 -0.104686 0.0217138 0.00692024 0.142748 +EDGE3 1065 1066 -0.798703 12.6303 -0.0217108 0.00554084 -0.056043 0.125246 +EDGE3 1066 1067 -0.831702 12.4412 -0.0811123 0.0410297 0.0128999 0.111193 +EDGE3 1067 1068 -1.04225 12.5657 -0.0694902 0.0116373 0.0549997 0.13377 +EDGE3 1068 1069 -0.990176 12.4967 -0.145739 0.0312609 0.0170363 0.106247 +EDGE3 1069 1070 -0.816414 12.6942 -0.0752947 0.0297632 0.0150448 0.151402 +EDGE3 1070 1071 -0.681553 12.4263 -0.0945759 -0.0175128 0.0252157 0.121203 +EDGE3 1071 1072 -0.703745 12.4857 -0.0767908 -0.00293553 0.0330753 0.0973052 +EDGE3 1072 1073 -0.839586 12.5044 -0.0280504 0.0528131 -0.0192426 0.0787383 +EDGE3 1073 1074 -0.924749 12.6256 -0.174491 0.0321006 -0.00313833 0.122073 +EDGE3 1074 1075 -0.765064 12.5144 0.0606124 0.0016112 -0.0353892 0.112808 +EDGE3 1075 1076 -0.787592 12.6311 -0.0778356 0.0331455 -0.0205273 0.140018 +EDGE3 1076 1077 -0.990849 12.6374 -0.229828 -0.000105282 -0.0273064 0.125833 +EDGE3 1077 1078 -0.801727 12.5354 0.0265144 0.0116702 -0.0139968 0.115083 +EDGE3 1078 1079 -0.623978 12.6615 -0.0939149 0.00704453 0.0318289 0.128861 +EDGE3 1079 1080 -0.756447 12.4542 -0.234464 -0.0319813 -0.0046501 0.120837 +EDGE3 1080 1081 -0.79652 12.4158 -0.115873 0.0177111 -0.0286509 0.13282 +EDGE3 1081 1082 -0.789525 12.4921 -0.206165 -0.0250937 -0.00800609 0.109927 +EDGE3 1082 1083 -0.833059 12.4333 -0.117314 0.0200546 0.00925566 0.099367 +EDGE3 1083 1084 -0.591853 12.3595 -0.0383181 -0.0029524 -0.0264318 0.123433 +EDGE3 1084 1085 -0.926778 12.6015 -0.224136 -0.0197319 0.00898412 0.126695 +EDGE3 1085 1086 -0.733089 12.3599 -0.106224 0.00546669 0.0245284 0.0991958 +EDGE3 1086 1087 -0.65631 12.6264 -0.150219 -0.014264 0.0470751 0.175067 +EDGE3 1087 1088 -0.465686 12.51 -0.119103 -0.00349824 -0.0307427 0.146987 +EDGE3 1088 1089 -0.933717 12.5656 0.109646 0.000632387 -0.0219584 0.107281 +EDGE3 1089 1090 -0.724227 12.5217 -0.234716 -0.0165076 -0.00572283 0.104309 +EDGE3 1090 1091 -0.717197 12.459 0.0821954 -0.0463596 -0.00898305 0.134268 +EDGE3 1091 1092 -0.969065 12.382 0.0296537 0.032643 -0.0516508 0.0982767 +EDGE3 1092 1093 -0.753424 12.6136 -0.0494608 -0.00204066 -0.00417727 0.0825469 +EDGE3 1093 1094 -0.797022 12.417 -0.14165 -0.00811949 -0.00552145 0.12937 +EDGE3 1094 1095 -1.01685 12.4773 -0.120251 0.0270233 0.00541681 0.0889332 +EDGE3 1095 1096 -0.857953 12.2914 -0.275835 -0.0122648 0.00764989 0.143949 +EDGE3 1096 1097 -0.68087 12.3926 -0.0729806 0.0239692 -0.0142844 0.141829 +EDGE3 1097 1098 -0.919982 12.4827 0.00187034 -0.00210643 0.0221727 0.111072 +EDGE3 1098 1099 -0.825996 12.6881 -0.165042 -0.0173384 -0.00451508 0.124043 +EDGE3 1099 1100 -0.858915 12.3649 -0.0271965 0.026845 -9.85807e-06 0.147287 +EDGE3 1100 1101 -0.772153 12.4102 -0.0623332 0.01447 0.0341856 0.169474 +EDGE3 1101 1102 -0.785761 12.6024 -0.144963 0.0479966 -0.00147985 0.120885 +EDGE3 1102 1103 -0.85271 12.2782 -0.00494598 -0.00622242 -0.0132988 0.139948 +EDGE3 1103 1104 -0.833367 12.6336 -0.281304 -0.0128805 0.01025 0.135782 +EDGE3 1104 1105 -0.755286 12.4609 -0.413721 -0.0191708 0.00827125 0.110034 +EDGE3 1105 1106 -0.742074 12.4623 -0.187391 0.00432955 0.00521205 0.135643 +EDGE3 1106 1107 -0.862454 12.5147 -0.116846 -0.0165442 0.0068695 0.181068 +EDGE3 1107 1108 -0.78334 12.3555 -0.0776388 -0.0543136 0.0258084 0.132024 +EDGE3 1108 1109 -0.823323 12.5004 0.0437409 -0.0214253 -0.0111727 0.110166 +EDGE3 1109 1110 -0.808854 12.3671 0.00198705 0.00623536 -0.0321668 0.120863 +EDGE3 1110 1111 -0.635779 12.5323 -0.115266 -0.0188159 0.0302042 0.110546 +EDGE3 1111 1112 -0.809074 12.719 0.0116912 0.00497934 -0.0211418 0.100699 +EDGE3 1112 1113 -0.71939 12.4927 -0.0315646 0.0135474 -0.0119496 0.147188 +EDGE3 1113 1114 -0.754315 12.4959 -0.264231 -0.00259993 0.00913415 0.17253 +EDGE3 1114 1115 -0.668579 12.5126 -0.107317 -0.000723847 0.00695196 0.151462 +EDGE3 1115 1116 -0.897525 12.6723 -0.102936 -0.0535634 0.0413187 0.16023 +EDGE3 1116 1117 -0.794323 12.522 -0.253217 0.00323741 -0.0335356 0.126145 +EDGE3 1117 1118 -0.651032 12.6022 -0.101413 0.0120751 -0.0270611 0.113199 +EDGE3 1118 1119 -0.776478 12.4911 -0.136575 0.0101979 -0.0253755 0.11864 +EDGE3 1119 1120 -0.733726 12.5121 -0.0102805 0.0117753 0.00405281 0.136651 +EDGE3 1120 1121 -0.911914 12.4526 -0.0131908 -0.0284082 -0.00875204 0.155088 +EDGE3 1121 1122 -0.860829 12.526 -0.0683573 0.0443302 -0.0218693 0.120775 +EDGE3 1122 1123 -0.721918 12.6046 -0.21373 0.0159194 -0.036437 0.121023 +EDGE3 1123 1124 -0.868351 12.5978 -0.139496 0.0167591 -0.0152655 0.108223 +EDGE3 1124 1125 -0.796384 12.5513 -0.131221 -0.0107527 -0.0111349 0.10225 +EDGE3 1125 1126 -0.788196 12.6125 -0.161816 -0.00315955 -0.0304467 0.151397 +EDGE3 1126 1127 -0.778603 12.6598 -0.0754588 0.0240203 -0.0124679 0.130594 +EDGE3 1127 1128 -0.908567 12.2984 0.00491043 0.0416383 -0.00636808 0.151772 +EDGE3 1128 1129 -0.855732 12.3899 -0.0698179 0.00811709 -0.0145261 0.118269 +EDGE3 1129 1130 -0.804651 12.3467 -0.0617064 0.0101954 -0.0255771 0.13636 +EDGE3 1130 1131 -0.710992 12.5994 -0.119558 0.0260809 0.0359178 0.136332 +EDGE3 1131 1132 -0.847771 12.4472 -0.156954 0.0229275 -0.00185368 0.111874 +EDGE3 1132 1133 -0.811202 12.3886 -0.387482 -0.00942735 -0.00132775 0.139869 +EDGE3 1133 1134 -0.7869 12.5172 -0.177601 0.0392972 -0.0149341 0.149887 +EDGE3 1134 1135 -0.817702 12.4248 -0.304638 -0.0380489 0.0133559 0.130093 +EDGE3 1135 1136 -0.58445 12.4536 -0.119818 0.0378513 0.0410753 0.110431 +EDGE3 1136 1137 -0.664822 12.5267 0.0231428 -0.0692308 0.00138725 0.133613 +EDGE3 1137 1138 -0.857431 12.5357 -0.150121 0.00397956 0.0181406 0.133225 +EDGE3 1138 1139 -0.888336 12.6292 -0.195213 0.00478887 0.0442317 0.140915 +EDGE3 1139 1140 -0.744867 12.3339 -0.00465638 0.00222677 0.00215427 0.121159 +EDGE3 1140 1141 -0.991314 12.5563 -0.023335 0.0144567 0.0117237 0.0927539 +EDGE3 1141 1142 -0.671108 12.5083 0.256103 -0.0434176 -0.0150734 0.117063 +EDGE3 1142 1143 -0.819006 12.5513 -0.260452 -0.0062211 0.0121409 0.129258 +EDGE3 1143 1144 -0.731941 12.5975 -0.163325 0.00906185 -0.0334905 0.138091 +EDGE3 1144 1145 -0.691764 12.5525 -0.250085 -0.04127 -0.0192603 0.116049 +EDGE3 1145 1146 -0.803703 12.4888 -0.195616 0.0063526 -0.00146383 0.11134 +EDGE3 1146 1147 -0.639592 12.6042 -0.236119 0.0319318 -0.0400727 0.187501 +EDGE3 1147 1148 -0.802389 12.6576 -0.223571 -0.0265324 -0.00120531 0.108159 +EDGE3 1148 1149 -0.749546 12.4741 -0.0879908 0.0367422 -0.0185836 0.145177 +EDGE3 1149 1150 -0.716935 12.6437 -0.209265 0.00281375 -0.0154812 0.113142 +EDGE3 1150 1151 -0.936019 12.3328 -0.221051 -0.0108293 -0.00789023 0.136028 +EDGE3 1151 1152 -0.73303 12.5943 -0.257879 0.00277937 -0.00838823 0.121128 +EDGE3 1152 1153 -0.849206 12.321 -0.0738153 0.00945629 0.0254735 0.126482 +EDGE3 1153 1154 -0.749741 12.492 0.0892094 -0.0387141 0.0225577 0.0938238 +EDGE3 1154 1155 -0.600096 12.5758 -0.143537 -0.00152963 0.0345001 0.102382 +EDGE3 1155 1156 -0.913824 12.6864 -0.377033 0.0427868 0.011256 0.108045 +EDGE3 1156 1157 -0.988468 12.405 -0.0783507 0.00347449 -0.000151338 0.127965 +EDGE3 1157 1158 -0.927428 12.4531 -0.0233127 -0.0322861 0.0239156 0.102982 +EDGE3 1158 1159 -0.797129 12.6712 -0.119019 -0.018228 -0.0115119 0.118505 +EDGE3 1159 1160 -0.84417 12.5614 -0.10585 -0.00954048 0.00478953 0.0926699 +EDGE3 1160 1161 -0.817871 12.5965 -0.0861484 0.0216967 -0.0320851 0.1156 +EDGE3 1161 1162 -0.735517 12.4585 -0.00154843 0.030331 0.00141573 0.113914 +EDGE3 1162 1163 -0.789226 12.3998 -0.302286 -0.0173661 0.0348246 0.067842 +EDGE3 1163 1164 -0.633133 12.4845 -0.146209 -0.0364115 -0.00340375 0.098432 +EDGE3 1164 1165 -0.7876 12.5508 -0.0393589 -0.0241999 0.00561999 0.132963 +EDGE3 1165 1166 -0.823789 12.5912 -0.0435388 0.0022122 0.033123 0.118373 +EDGE3 1166 1167 -0.930948 12.4261 -0.191883 -0.041044 -0.0116811 0.132732 +EDGE3 1167 1168 -0.763355 12.4847 -0.0787949 0.00776993 -0.0122851 0.103003 +EDGE3 1168 1169 -0.856148 12.3922 -0.204437 0.039647 0.020311 0.145123 +EDGE3 1169 1170 -0.785115 12.4417 -0.118671 -0.00472596 0.0293514 0.127414 +EDGE3 1170 1171 -0.748856 12.404 -0.242712 -0.0206827 0.0304359 0.135246 +EDGE3 1171 1172 -0.8625 12.4146 0.0104258 -0.0246914 0.03911 0.150619 +EDGE3 1172 1173 -0.790135 12.713 -0.0729537 -0.0111894 -0.0492399 0.119697 +EDGE3 1173 1174 -0.89193 12.402 -0.238788 -0.0147997 0.016507 0.153249 +EDGE3 1174 1175 -0.735006 12.531 -0.110458 0.0296792 -0.00687659 0.121304 +EDGE3 1175 1176 -0.722321 12.5275 0.0300987 0.0172517 0.0205361 0.174112 +EDGE3 1176 1177 -0.782931 12.5222 -0.0501092 0.0172428 -0.00397769 0.161583 +EDGE3 1177 1178 -0.693008 12.5711 -0.21346 0.0127482 0.018479 0.0959852 +EDGE3 1178 1179 -0.766151 12.4991 -0.00995519 -0.0468468 0.0301627 0.121027 +EDGE3 1179 1180 -0.751762 12.3618 -0.19722 0.0152374 0.0128254 0.129581 +EDGE3 1180 1181 -0.657175 12.4211 -0.139112 -0.0208983 -0.00754057 0.102347 +EDGE3 1181 1182 -0.77584 12.4945 -0.102264 0.0321366 -0.0081119 0.115284 +EDGE3 1182 1183 -0.783642 12.5516 -0.18892 -0.00945349 -0.0141636 0.100705 +EDGE3 1183 1184 -0.677123 12.4139 -0.0848239 -0.0138487 -0.00531698 0.151948 +EDGE3 1184 1185 -0.776482 12.4234 -0.33341 -0.012839 -0.00574343 0.145001 +EDGE3 1185 1186 -0.850756 12.3156 -0.1402 0.0632415 -0.000272199 0.0819622 +EDGE3 1186 1187 -0.957324 12.3395 -0.230737 -0.0174201 0.041367 0.146066 +EDGE3 1187 1188 -0.796333 12.3511 -0.41599 0.0159921 -0.00975515 0.129375 +EDGE3 1188 1189 -0.852928 12.3758 -0.207563 -0.0508036 0.0176112 0.141099 +EDGE3 1189 1190 -0.872272 12.3317 -0.0503095 0.00894568 0.00144999 0.0699763 +EDGE3 1190 1191 -0.544967 12.3648 -0.114126 0.0213397 0.0177479 0.147981 +EDGE3 1191 1192 -0.776307 12.5664 -0.121353 0.0113748 0.0147404 0.0756688 +EDGE3 1192 1193 -0.702309 12.3447 -0.013556 -0.00781213 -0.00893891 0.11442 +EDGE3 1193 1194 -0.69813 12.538 -0.0611002 -0.0190521 -0.0083518 0.0688788 +EDGE3 1194 1195 -0.853062 12.4697 0.037131 -0.0038554 -0.0376803 0.146687 +EDGE3 1196 1197 -0.861133 12.4181 -0.0545411 -0.0424741 -0.00911003 0.129386 +EDGE3 1195 1196 -0.712554 12.422 -0.159236 0.0155645 -0.00482563 0.180342 +EDGE3 1198 1199 -0.845607 12.3727 -0.0574562 -0.00190775 -0.0233758 0.160973 +EDGE3 1197 1198 -0.751045 12.6032 -0.267506 -0.00851468 -0.00832336 0.121196 +EDGE3 1200 1201 -0.80668 12.4819 -0.228459 -0.0141935 -0.0174682 0.148114 +EDGE3 1199 1200 -0.902277 12.4033 -0.0312846 0.021594 -0.0217372 0.102764 +EDGE3 1202 1203 -0.722074 12.3318 -0.145612 -0.00995298 -0.00089475 0.115223 +EDGE3 1201 1202 -0.667427 12.4091 -0.26436 -0.0242534 0.0314238 0.155284 +EDGE3 1204 1205 -0.673241 12.3767 -0.0468558 0.0301398 -0.0108884 0.140457 +EDGE3 1203 1204 -0.678486 12.4176 -0.119364 -0.0130957 -0.0157687 0.129614 +EDGE3 1206 1207 -0.886947 12.4257 -0.225643 -0.0124275 -0.00630303 0.127085 +EDGE3 1205 1206 -1.02723 12.4637 -0.385809 0.00157578 -0.0232944 0.141481 +EDGE3 1208 1209 -0.988785 12.3833 -0.213264 0.0404305 -0.000324879 0.153387 +EDGE3 1207 1208 -0.710404 12.3052 -0.0545979 0.0142867 -0.0143264 0.0995945 +EDGE3 1210 1211 -0.861428 12.2404 -0.0238624 -0.0172973 -0.0103933 0.111399 +EDGE3 1209 1210 -0.783643 12.4919 -0.0648402 -0.0516596 -0.0146461 0.123738 +EDGE3 1212 1213 -0.839693 12.3961 -0.0604631 0.00889217 0.0288303 0.138794 +EDGE3 1211 1212 -0.822085 12.2858 -0.131934 -0.0291164 -0.00326437 0.155672 +EDGE3 1214 1215 -0.702483 12.3166 -0.125061 0.00479767 -0.0241418 0.140614 +EDGE3 1213 1214 -0.681827 12.4016 -0.222287 0.00547444 0.0294125 0.132737 +EDGE3 1216 1217 -0.716699 12.4926 -0.143158 -0.00327405 0.0034653 0.140385 +EDGE3 1215 1216 -0.843242 12.309 -0.0763986 -0.0307148 -0.0130668 0.119268 +EDGE3 1218 1219 -0.772705 12.4024 -0.215492 -0.000352322 -0.0174578 0.119366 +EDGE3 1217 1218 -0.756967 12.3564 -0.144785 -0.0236129 -0.00347629 0.107003 +EDGE3 1220 1221 -0.700779 12.3706 -0.126685 0.00379263 0.0144208 0.0943649 +EDGE3 1219 1220 -0.808667 12.1974 0.0570679 -0.00311913 -0.0461368 0.146269 +EDGE3 1222 1223 -0.670966 12.2531 -0.171491 -0.00374155 -0.00412058 0.116419 +EDGE3 1221 1222 -0.866031 12.2959 -0.33312 0.0434942 -0.0262303 0.142853 +EDGE3 1224 1225 -0.884302 12.2937 -0.123316 -0.0295333 0.0473116 0.160529 +EDGE3 1223 1224 -0.8776 12.3149 -0.11356 -0.00221338 0.0139828 0.14119 +EDGE3 1226 1227 -0.806892 12.3633 -0.0123984 -0.000127234 -0.00349064 0.136879 +EDGE3 1225 1226 -0.79282 12.4909 -0.0899478 -0.0276372 0.0299006 0.149449 +EDGE3 1227 1228 -0.860151 12.2867 -0.0184986 0.0523384 0.0162535 0.119475 +EDGE3 1228 1229 -0.790172 12.4609 0.0899135 0.0171633 0.0432199 0.14999 +EDGE3 1230 1231 -0.816158 12.4524 -0.131123 -0.00996922 -0.00380826 0.140953 +EDGE3 1229 1230 -1.00305 12.4599 0.154766 -0.00802493 -0.00614235 0.139232 +EDGE3 1232 1233 -0.719502 12.2225 -0.217832 0.0370142 -0.0253072 0.133426 +EDGE3 1231 1232 -1.00965 12.2733 -0.107555 0.0323453 -0.0424615 0.111498 +EDGE3 1234 1235 -0.697948 12.2642 -0.0589788 -0.0205887 0.0121659 0.121964 +EDGE3 1233 1234 -0.813467 12.4608 -0.151524 0.00478477 0.0129009 0.0786574 +EDGE3 1236 1237 -0.762126 12.4229 -0.169406 -0.0393205 0.0167299 0.13461 +EDGE3 1235 1236 -0.748305 12.3458 -0.173462 0.0117476 -0.0119367 0.155289 +EDGE3 1238 1239 -0.862671 12.3948 -0.0546003 0.00415348 -0.00257711 0.0974128 +EDGE3 1237 1238 -0.743788 12.3236 -0.00411578 0.0306769 0.0132594 0.105509 +EDGE3 1239 1240 -0.803885 12.2117 -0.0834363 -0.0162548 0.0242856 0.0989188 +EDGE3 1240 1241 -0.812326 12.4017 -0.0437063 -0.0292471 -0.0252176 0.148336 +EDGE3 1242 1243 -0.781459 12.3264 -0.023355 -0.00608859 0.0493463 0.17668 +EDGE3 1241 1242 -0.852638 12.3511 -0.206032 -0.00610804 0.00874669 0.119898 +EDGE3 1244 1245 -0.950813 12.2909 -0.0740868 -0.00962383 0.0124166 0.11645 +EDGE3 1243 1244 -0.680246 12.4943 -0.0766248 -0.0139339 -0.0344716 0.101515 +EDGE3 1246 1247 -0.938563 12.3153 -0.176809 -0.0197283 0.00691395 0.131552 +EDGE3 1245 1246 -0.969925 12.1355 -0.121222 -0.020854 -0.0310131 0.128255 +EDGE3 1248 1249 -0.836884 12.3692 -0.138954 -0.0195941 -0.0215527 0.0946925 +EDGE3 1247 1248 -0.80511 12.219 -0.171564 0.00259103 0.0230244 0.145368 +EDGE3 1250 1251 -0.769846 12.3328 -0.254269 -0.00867739 0.0274762 0.136517 +EDGE3 1249 1250 -0.606475 12.2878 -0.157212 0.00851567 0.0406143 0.117254 +EDGE3 1252 1253 -0.723394 12.2781 -0.313188 -0.00642307 0.00325152 0.13004 +EDGE3 1251 1252 -0.931364 12.3285 -0.147633 0.0030453 0.00426807 0.113662 +EDGE3 1254 1255 -0.765652 12.2466 -0.166886 -0.0101955 -0.00618195 0.143135 +EDGE3 1253 1254 -0.691007 12.2354 -0.143707 -0.010361 -0.0102161 0.130414 +EDGE3 1256 1257 -0.858177 12.2573 -0.158425 0.0356095 0.0571238 0.16801 +EDGE3 1255 1256 -0.796502 12.4437 -0.0130356 -0.00527113 -0.0106525 0.132048 +EDGE3 1258 1259 -0.737669 12.4091 -0.180379 0.0176887 0.0341503 0.127268 +EDGE3 1257 1258 -0.746751 12.1851 -0.136577 0.000548884 0.0164011 0.111759 +EDGE3 1260 1261 -0.799662 12.2056 -0.201153 0.0245346 -0.0393064 0.116588 +EDGE3 1259 1260 -0.614564 12.4215 -0.067711 -0.0181053 0.023508 0.137064 +EDGE3 1262 1263 -0.79533 12.2346 -0.126395 0.0131611 0.00959128 0.132933 +EDGE3 1261 1262 -0.806833 12.3519 -0.0439146 0.0291913 0.00446906 0.113079 +EDGE3 1264 1265 -0.76675 12.4134 -0.231076 0.0237018 0.0183025 0.143347 +EDGE3 1263 1264 -0.759006 12.2137 -0.0116762 -0.0583745 -0.0163062 0.142273 +EDGE3 1266 1267 -0.891209 12.2678 -0.063428 0.0299251 -0.000640529 0.137764 +EDGE3 1265 1266 -0.766429 12.2505 -0.192683 0.0114053 -0.013732 0.163833 +EDGE3 1268 1269 -0.650854 12.2238 -0.0875825 -0.022698 -0.00379764 0.170215 +EDGE3 1267 1268 -0.819702 12.4449 -0.098448 0.0659571 -0.0073964 0.0715519 +EDGE3 1270 1271 -0.84125 12.3193 -0.160556 -0.0136565 0.0183058 0.101217 +EDGE3 1269 1270 -0.735243 12.3631 -0.058338 0.00676789 -0.0469137 0.129961 +EDGE3 1271 1272 -0.591237 12.3282 -0.0865608 -0.00471564 -0.00318567 0.132424 +EDGE3 1272 1273 -0.769951 12.3133 -0.282971 0.0112926 -0.0473084 0.103424 +EDGE3 1273 1274 -0.883183 12.2623 -0.0518669 0.0231263 -0.0169026 0.145245 +EDGE3 1275 1276 -0.828858 12.1287 -0.265766 0.012077 0.0262825 0.121718 +EDGE3 1274 1275 -0.988851 12.212 -0.0670057 0.0367974 0.00325669 0.141122 +EDGE3 1277 1278 -0.784786 12.3763 -0.172246 -0.0227695 0.00810399 0.140919 +EDGE3 1276 1277 -0.74237 12.1641 -0.208523 -0.0538659 0.0235538 0.130633 +EDGE3 1279 1280 -0.888104 12.1118 -0.0185607 0.025373 0.00235985 0.0836864 +EDGE3 1278 1279 -0.929166 12.3988 -0.1247 0.031497 -0.0455582 0.137022 +EDGE3 1281 1282 -0.664597 12.0971 -0.0167583 0.00360117 0.0163293 0.112967 +EDGE3 1280 1281 -0.868137 12.331 -0.170373 0.0158178 -0.023355 0.128839 +EDGE3 1283 1284 -0.626211 12.1559 -0.145243 0.0197651 -0.0227788 0.139504 +EDGE3 1282 1283 -0.797237 12.2269 -0.0686978 -0.00518878 0.0229453 0.158277 +EDGE3 1285 1286 -0.907458 12.0382 -0.191678 -0.0129944 0.0302146 0.0955465 +EDGE3 1284 1285 -0.823607 12.0479 -0.0809862 0.040098 0.0265536 0.16812 +EDGE3 1287 1288 -0.919614 12.3106 0.217546 -0.011072 -0.0351878 0.0939521 +EDGE3 1286 1287 -0.789442 12.2897 -0.207579 -0.00652209 -0.0118296 0.127173 +EDGE3 1289 1290 -0.759629 12.3178 -0.120001 0.0446145 0.0562033 0.130228 +EDGE3 1288 1289 -0.955676 12.36 -0.0875679 -0.0169318 0.00885564 0.147673 +EDGE3 1291 1292 -0.92057 12.3099 -0.239487 0.0049801 -0.00611858 0.184877 +EDGE3 1290 1291 -0.801111 12.2154 -0.394202 0.0120607 0.00158057 0.0941174 +EDGE3 1293 1294 -0.781873 12.1643 -0.0925599 0.0117655 -0.0156562 0.151304 +EDGE3 1292 1293 -0.758101 12.1323 0.018594 -0.0291584 -0.00468972 0.12606 +EDGE3 1295 1296 -0.793388 12.0793 -0.185524 0.012752 0.0232685 0.134681 +EDGE3 1294 1295 -0.742573 11.9303 -0.184643 -0.0320537 -0.00670904 0.114304 +EDGE3 1297 1298 -0.754169 12.0977 -0.320613 -0.0070434 0.010235 0.136003 +EDGE3 1296 1297 -0.67201 12.3085 -0.200004 -0.0484806 -0.0325451 0.128451 +EDGE3 1299 1300 -0.73058 12.1956 -0.202637 -0.0108407 0.0698999 0.116711 +EDGE3 1298 1299 -0.789573 12.2183 -0.208253 -0.00430319 0.0225841 0.089825 +EDGE3 1301 1302 -0.945178 12.156 -0.134329 0.0289662 0.0106269 0.133167 +EDGE3 1300 1301 -0.882569 12.034 -0.024424 0.0123463 0.0250567 0.112304 +EDGE3 1303 1304 -0.836201 12.2291 -0.264556 0.0152187 0.0330022 0.124654 +EDGE3 1302 1303 -0.730557 11.9861 -0.227482 0.0291296 0.01263 0.100409 +EDGE3 1304 1305 -0.702553 12.1394 -0.184521 0.0227313 -0.0109202 0.139177 +EDGE3 1305 1306 -0.791688 12.1324 0.106315 -0.0095733 -0.0272333 0.102289 +EDGE3 1306 1307 -0.935688 12.0418 -0.00694845 -0.00253757 0.0130594 0.125389 +EDGE3 1307 1308 -0.713379 12.1097 -0.138882 0.0213719 0.0228486 0.117072 +EDGE3 1308 1309 -0.966686 12.1262 0.0341837 -0.047567 -0.0139987 0.108238 +EDGE3 1309 1310 -0.811815 12.0413 -0.195317 0.0228135 0.0030112 0.112337 +EDGE3 1310 1311 -0.982287 12.2707 -0.017432 -0.00365071 0.0165951 0.138207 +EDGE3 1311 1312 -0.983701 11.9804 0.145028 0.00343086 -0.00797887 0.115199 +EDGE3 1312 1313 -0.825672 12.0367 0.0275205 -0.000468846 0.0127843 0.123156 +EDGE3 1313 1314 -0.823716 12.1114 -0.0441964 0.0242275 -0.0213864 0.111801 +EDGE3 1314 1315 -0.799025 11.9701 -0.013472 0.00808835 0.0031495 0.107076 +EDGE3 1315 1316 -0.861002 11.8915 -0.121361 -0.0147643 0.0171523 0.11254 +EDGE3 1316 1317 -0.729512 12.0466 -0.249011 -0.00774228 -0.0050502 0.138429 +EDGE3 1317 1318 -0.735584 12.1696 -0.0160353 0.0144281 0.018214 0.166206 +EDGE3 1318 1319 -0.990533 11.8331 -0.24167 0.054792 0.00970411 0.148109 +EDGE3 1319 1320 -0.86178 12.1703 -0.186876 -0.043775 0.0771451 0.146378 +EDGE3 1320 1321 -0.793556 12.1056 -0.228617 -0.0208618 -0.0232394 0.0935922 +EDGE3 1321 1322 -0.758953 12.0865 -0.0303057 -0.0140141 0.0258464 0.146609 +EDGE3 1322 1323 -0.737868 11.8571 0.0233552 0.00245447 0.0304675 0.0883039 +EDGE3 1323 1324 -0.804965 12.3022 -0.247828 0.0237053 -0.0175099 0.146459 +EDGE3 1324 1325 -0.717003 11.9212 -0.00331699 0.00937107 0.00687555 0.156716 +EDGE3 1325 1326 -1.00768 12.1694 -0.133516 -0.00693954 0.0145239 0.119644 +EDGE3 1326 1327 -0.629665 12.0505 -0.131829 -0.0107651 0.0118886 0.119028 +EDGE3 1327 1328 -0.984617 12.0183 -0.0843823 0.00167344 -0.00424255 0.1661 +EDGE3 1328 1329 -0.933936 12.1076 -0.0293551 -0.0127874 -0.0180616 0.102034 +EDGE3 1329 1330 -1.0146 11.9573 -0.0958437 0.00757741 0.0100863 0.108842 +EDGE3 1330 1331 -0.650533 11.9312 -0.130486 0.0028506 -0.012938 0.101266 +EDGE3 1331 1332 -0.900239 12.0154 -0.22497 0.0212258 -0.00250526 0.146527 +EDGE3 1332 1333 -0.747805 11.9054 -0.245036 -0.0101559 0.00828855 0.141268 +EDGE3 1333 1334 -0.753453 12.0182 0.0529639 0.0641287 -0.00780485 0.124629 +EDGE3 1334 1335 -0.770693 11.8443 -0.25502 -0.00123542 0.0064145 0.117986 +EDGE3 1335 1336 -0.695679 12.0943 -0.168065 -0.0204761 0.0490668 0.113296 +EDGE3 1336 1337 -0.744405 11.9031 -0.212637 0.0290468 0.0157393 0.151736 +EDGE3 1337 1338 -0.771289 11.7711 -0.0411591 -0.0289121 0.0124695 0.155669 +EDGE3 1338 1339 -0.826106 11.9936 -0.145368 0.0206775 -0.00169836 0.0801288 +EDGE3 1339 1340 -0.782837 12.0873 -0.0800497 0.025886 0.018826 0.123696 +EDGE3 1340 1341 -0.66962 12.1338 0.154884 -0.0327428 -0.0443728 0.147588 +EDGE3 1341 1342 -0.803471 11.9545 0.0855889 0.0161247 0.00782076 0.10747 +EDGE3 1342 1343 -0.743322 11.9014 -0.182173 -0.0295864 -0.0106612 0.163383 +EDGE3 1343 1344 -0.944872 12.074 -0.218413 -0.0615357 -0.00020445 0.107335 +EDGE3 1344 1345 -0.747414 11.8612 -0.194711 -0.0501881 0.00797458 0.126083 +EDGE3 1345 1346 -0.824218 11.9013 -0.154884 -0.00863052 -0.0126516 0.0982118 +EDGE3 1346 1347 -0.842135 11.8166 -0.180752 -0.0333679 0.0192797 0.117598 +EDGE3 1347 1348 -0.840643 12.0078 -0.0841456 -0.00959472 0.0174407 0.130311 +EDGE3 1348 1349 -0.774275 11.972 -0.120342 0.00693938 0.0565239 0.0985948 +EDGE3 1349 1350 -0.832251 11.8432 -0.102235 -0.0264931 0.0181544 0.124893 +EDGE3 1350 1351 -0.779054 12.0336 -0.290394 -0.0102469 -0.00447793 0.098528 +EDGE3 1351 1352 -0.786555 11.9526 -0.0226899 -0.016668 0.0602669 0.0877403 +EDGE3 1352 1353 -0.798062 11.9416 -0.0558789 -0.00666802 -0.0165047 0.0878853 +EDGE3 1353 1354 -0.700096 11.9539 -0.171745 -0.0349201 -0.0208252 0.167667 +EDGE3 1354 1355 -0.719402 11.9779 0.113515 -0.013193 0.00113915 0.120793 +EDGE3 1355 1356 -0.79139 11.6873 -0.331983 0.0179002 -0.0328026 0.0940167 +EDGE3 1356 1357 -0.784704 11.7875 -0.0382493 -0.0299714 0.0213664 0.0721916 +EDGE3 1357 1358 -0.762963 11.8764 0.0466898 0.0163282 -0.0196949 0.116623 +EDGE3 1358 1359 -0.798901 11.6667 -0.11002 -0.0319706 0.00672098 0.149647 +EDGE3 1359 1360 -0.814716 11.8394 -0.0592042 -0.0427142 0.0474467 0.0730908 +EDGE3 1360 1361 -0.689121 11.917 0.00332776 0.00714921 0.00593088 0.132905 +EDGE3 1361 1362 -0.660026 11.8077 -0.186604 -0.00163899 -0.0526037 0.158285 +EDGE3 1362 1363 -0.822355 11.6923 0.0296671 0.0264888 0.0463792 0.129634 +EDGE3 1363 1364 -0.814428 11.7786 -0.171731 -0.02146 -0.00596728 0.136569 +EDGE3 1364 1365 -0.579423 11.8241 -0.0858328 -0.0575565 0.0485542 0.0833544 +EDGE3 1365 1366 -0.665442 11.9109 -0.0967144 0.0025702 0.00524053 0.108089 +EDGE3 1366 1367 -0.722304 11.8761 -0.0313011 -0.0469573 -0.0408388 0.151373 +EDGE3 1367 1368 -0.682696 11.8446 -0.36714 0.0277877 -0.0054819 0.121762 +EDGE3 1368 1369 -0.856309 11.8939 -0.0768773 -0.0200263 0.0160288 0.0992931 +EDGE3 1369 1370 -0.897246 11.8349 -0.115679 0.0153567 -0.0113878 0.106408 +EDGE3 1370 1371 -0.856552 11.9573 -0.259284 0.00462919 -0.0166829 0.168378 +EDGE3 1371 1372 -0.76779 11.8113 -0.0931533 0.0281835 0.0471003 0.110785 +EDGE3 1372 1373 -0.744916 11.9064 -0.170095 0.0119182 -0.0136532 0.0915877 +EDGE3 1373 1374 -0.825192 11.9023 -0.127432 -0.0342841 0.00730106 0.147814 +EDGE3 1374 1375 -0.811616 11.7436 0.0820167 0.0307064 -0.000783944 0.0856391 +EDGE3 1375 1376 -0.586391 11.8062 -0.0672479 0.00183668 -0.0226567 0.157618 +EDGE3 1376 1377 -0.819068 11.9438 -0.119926 -0.0408053 0.0131732 0.127633 +EDGE3 1377 1378 -0.839271 11.8362 -0.118041 -0.0480242 0.0111452 0.112669 +EDGE3 1378 1379 -0.666394 11.8042 -0.252287 -0.020601 -0.00282024 0.0859291 +EDGE3 1379 1380 -0.768884 11.6379 -0.146264 -0.0128409 -0.066376 0.103683 +EDGE3 1380 1381 -0.921111 11.8447 -0.182707 0.00115635 0.0178621 0.131413 +EDGE3 1381 1382 -0.737121 11.8152 -0.11212 0.018377 0.00358594 0.123183 +EDGE3 1382 1383 -0.805375 11.8113 -0.0169906 0.0373025 -0.00245433 0.148791 +EDGE3 1383 1384 -0.871585 11.7365 -0.290456 0.0161881 0.0444514 0.137575 +EDGE3 1384 1385 -0.778345 11.9838 -0.0138095 0.00833746 -0.00561478 0.0797175 +EDGE3 1385 1386 -0.590383 11.7688 -0.258004 0.0298175 0.0220758 0.102266 +EDGE3 1386 1387 -0.900737 11.7975 -0.0425456 -0.0054614 0.0146762 0.140778 +EDGE3 1387 1388 -0.733355 11.5802 -0.137701 0.0297265 0.000795569 0.164939 +EDGE3 1388 1389 -0.975583 11.898 -0.12008 -0.0216711 -0.0202621 0.0806006 +EDGE3 1389 1390 -0.969744 11.7388 -0.152364 0.00900466 -0.00422325 0.111515 +EDGE3 1390 1391 -0.871444 11.688 -0.122702 -0.0133609 0.0136091 0.149733 +EDGE3 1391 1392 -0.829461 11.8717 -0.0986319 -0.0309951 -0.00206554 0.150517 +EDGE3 1392 1393 -0.676338 11.6227 -0.0283759 0.0468111 0.0103981 0.146265 +EDGE3 1393 1394 -0.542889 11.7129 -0.143317 -0.00242164 -0.00330196 0.147251 +EDGE3 1394 1395 -0.768617 11.7596 -0.0441211 0.00378035 -0.00610623 0.118017 +EDGE3 1395 1396 -0.635278 11.7682 -0.134542 0.00854777 0.036817 0.0812196 +EDGE3 1396 1397 -0.6104 11.6663 -0.187143 0.0356053 -0.0245132 0.144709 +EDGE3 1397 1398 -0.893405 11.6276 -0.154773 -0.0436727 0.000313128 0.130832 +EDGE3 1398 1399 -0.846959 11.5714 -0.356598 0.000758036 0.00339251 0.103303 +EDGE3 1399 1400 -0.693171 11.4969 -0.297452 0.00994171 0.0188534 0.123821 +EDGE3 1400 1401 -0.796185 11.7212 -0.009858 -0.0315123 0.0159471 0.140022 +EDGE3 1401 1402 -0.827763 11.7785 -0.188607 -0.0141076 0.0136513 0.136725 +EDGE3 1402 1403 -0.787718 11.6683 -0.191096 0.0197769 0.00950959 0.103896 +EDGE3 1403 1404 -0.77952 11.6848 -0.0536958 0.0223559 0.00456974 0.119348 +EDGE3 1404 1405 -0.959704 11.7649 0.0348177 -0.061575 0.00536396 0.156093 +EDGE3 1405 1406 -0.712966 11.6692 -0.0804254 -0.00884551 -0.00925545 0.124502 +EDGE3 1406 1407 -0.820816 11.6123 -0.0364543 -0.00701027 -0.00997736 0.165811 +EDGE3 1407 1408 -0.82251 11.6059 -0.128308 -0.0111028 -0.0168345 0.0506063 +EDGE3 1408 1409 -0.821776 11.5633 -0.396898 0.0256322 -0.0190286 0.144005 +EDGE3 1410 1411 -0.876479 11.6207 -0.0793301 -0.0032306 0.0209685 0.117338 +EDGE3 1409 1410 -0.710045 11.5475 -0.0284623 -0.0115149 -0.0113998 0.121515 +EDGE3 1411 1412 -0.856749 11.6937 0.0255868 0.027961 -0.0213085 0.0989736 +EDGE3 1412 1413 -0.763543 11.7598 -0.14573 0.0449363 -0.0202933 0.166212 +EDGE3 1413 1414 -0.680835 11.6897 -0.155915 -0.00405386 0.0380819 0.0851686 +EDGE3 1414 1415 -0.778176 11.6399 -0.151085 0.00195139 -0.0159879 0.108327 +EDGE3 1415 1416 -0.741368 11.5399 -0.20159 0.00654486 -0.00726792 0.177794 +EDGE3 1416 1417 -0.91147 11.5006 0.000404051 0.0118345 0.00969925 0.0993426 +EDGE3 1417 1418 -0.657594 11.6394 -0.0657549 -0.0143215 0.0248796 0.125337 +EDGE3 1418 1419 -0.871444 11.5047 -0.262347 0.0577808 0.0271843 0.126636 +EDGE3 1419 1420 -0.897742 11.5818 -0.120179 0.0270982 0.0061948 0.136262 +EDGE3 1420 1421 -0.812095 11.6808 -0.136057 0.000884894 0.000597447 0.135071 +EDGE3 1421 1422 -0.776001 11.6524 -0.282054 -0.0150095 -0.0236921 0.11237 +EDGE3 1422 1423 -0.613431 11.3701 0.0157257 -0.0200309 -0.0350426 0.106018 +EDGE3 1423 1424 -0.841308 11.3794 -0.174224 -0.00594777 0.0154246 0.169812 +EDGE3 1424 1425 -0.665214 11.3418 0.0174502 -0.0279905 -0.0410385 0.123049 +EDGE3 1425 1426 -0.649516 11.6404 0.0293444 -0.0327545 0.00547115 0.140387 +EDGE3 1426 1427 -0.893391 11.4727 -0.235329 -0.00464517 -0.0253355 0.111074 +EDGE3 1427 1428 -0.716273 11.6328 -0.216738 0.010056 0.0129966 0.130839 +EDGE3 1428 1429 -0.733729 11.3917 -0.269975 -0.00393141 0.0187485 0.0921307 +EDGE3 1429 1430 -0.813826 11.4885 -0.0806007 0.0799635 0.0281475 0.167696 +EDGE3 1430 1431 -0.828383 11.5524 -0.172817 -0.0132395 -0.0130521 0.170482 +EDGE3 1431 1432 -0.806366 11.6873 -0.0609479 -0.00397904 0.0401142 0.113959 +EDGE3 1432 1433 -0.806661 11.5081 -0.0578801 -0.0155841 -0.052093 0.100963 +EDGE3 1433 1434 -0.599341 11.5539 -0.252967 -0.0140946 -0.0257361 0.131702 +EDGE3 1434 1435 -0.868387 11.3653 -0.339184 0.00368109 0.00380729 0.129812 +EDGE3 1435 1436 -0.786055 11.3047 -0.0786072 -0.0318224 -0.0170316 0.114299 +EDGE3 1436 1437 -0.850573 11.1946 -0.0672425 -0.00803865 -0.0498899 0.162521 +EDGE3 1437 1438 -0.603858 11.5023 -0.141589 0.00451381 0.0243574 0.128579 +EDGE3 1438 1439 -0.801626 11.3986 -0.13742 -0.00436166 -0.0560819 0.146774 +EDGE3 1439 1440 -0.700423 11.3599 -0.0369072 0.00301212 0.0408504 0.118363 +EDGE3 1440 1441 -0.774697 11.4406 0.0101551 0.0242244 -0.00530323 0.139772 +EDGE3 1441 1442 -0.812613 11.2173 -0.155805 -0.0322704 -0.0238879 0.109239 +EDGE3 1442 1443 -0.607804 11.3752 -0.0596414 0.0594983 -0.0664418 0.0835887 +EDGE3 1443 1444 -0.838306 11.328 -0.267443 0.00768937 0.0192162 0.124551 +EDGE3 1444 1445 -0.78955 11.3559 -0.0680996 0.0278957 -0.000737604 0.16213 +EDGE3 1445 1446 -0.812158 11.3339 -0.0249855 0.00742199 0.00554896 0.1171 +EDGE3 1446 1447 -0.882546 11.3717 -0.145949 -0.00651766 -0.00797405 0.166311 +EDGE3 1447 1448 -0.690989 11.3228 0.0248374 0.0215674 -0.0247041 0.162759 +EDGE3 1448 1449 -0.837859 11.2483 -0.195422 -0.0459137 -0.00813576 0.0800538 +EDGE3 1449 1450 -0.782263 11.5688 0.100273 -0.0262383 0.0304964 0.138808 +EDGE3 1450 1451 -0.760442 11.3001 -0.158593 0.0178551 0.0182557 0.14619 +EDGE3 1451 1452 -0.967307 11.3302 -0.0686258 -0.0202678 0.000495313 0.0888337 +EDGE3 1452 1453 -0.80471 11.2074 -0.114732 -0.0112914 0.00496791 0.17872 +EDGE3 1453 1454 -0.921578 11.2433 -0.0610521 0.00135609 -0.0129158 0.090625 +EDGE3 1454 1455 -0.75371 11.3546 -0.274965 0.0114079 -0.039285 0.115953 +EDGE3 1455 1456 -0.745355 11.1681 -0.223118 0.0123589 -0.028418 0.192386 +EDGE3 1456 1457 -0.754116 11.2956 -0.181995 0.00184101 -0.00914509 0.0797238 +EDGE3 1458 1459 -0.849999 11.1177 -0.15955 0.0178027 0.0257186 0.159379 +EDGE3 1457 1458 -0.876006 11.3497 -0.146994 -0.0391045 -0.0376052 0.125674 +EDGE3 1459 1460 -0.590112 11.2111 -0.188623 -0.000457719 0.00486483 0.133515 +EDGE3 1461 1462 -0.704637 11.256 -0.11585 -0.00602132 -0.0319319 0.10829 +EDGE3 1460 1461 -0.837583 11.3456 -0.111729 -0.0543936 -0.0102497 0.0990217 +EDGE3 1463 1464 -0.767407 11.3036 -0.188317 -0.0135848 0.0194825 0.11208 +EDGE3 1462 1463 -0.724378 11.3264 0.018622 0.000118991 -0.0553296 0.133517 +EDGE3 1465 1466 -0.95251 11.0561 -0.19506 -0.0142185 -0.0239008 0.0968331 +EDGE3 1464 1465 -0.870734 11.3247 -0.124523 -0.00027597 0.0177895 0.0931748 +EDGE3 1467 1468 -0.708355 11.2657 -0.143747 0.017014 0.0420845 0.0882473 +EDGE3 1466 1467 -0.831784 11.2277 -0.201753 -0.0270441 -0.0122548 0.118756 +EDGE3 1469 1470 -0.62715 11.3087 -0.0480176 0.0350884 0.0270743 0.100753 +EDGE3 1468 1469 -0.694412 11.4101 -0.10874 -0.0144114 0.00636916 0.153123 +EDGE3 1471 1472 -0.895712 11.2816 -0.131131 -0.0352698 0.0314744 0.11232 +EDGE3 1470 1471 -0.88351 11.0799 -0.0110643 -0.0185043 0.0270078 0.117324 +EDGE3 1473 1474 -0.77596 11.1113 -0.0815159 0.0225371 0.0406637 0.134382 +EDGE3 1472 1473 -0.9131 10.851 -0.330717 0.0244994 0.0198407 0.11724 +EDGE3 1475 1476 -0.770635 10.9133 -0.0572933 0.0562031 0.0100874 0.124178 +EDGE3 1474 1475 -0.593468 11.1918 -0.0725627 0.0160431 -0.0199526 0.12497 +EDGE3 1477 1478 -0.662065 11.1213 -0.113727 -0.0235817 0.0236609 0.142745 +EDGE3 1476 1477 -0.805332 11.1856 -0.212281 -0.00230514 0.0257032 0.148823 +EDGE3 1479 1480 -0.710236 11.1029 -0.256448 0.0342344 -0.0345521 0.134626 +EDGE3 1478 1479 -0.789311 10.9183 -0.152258 0.00977046 0.0328559 0.10948 +EDGE3 1481 1482 -0.679895 11.1791 -0.161556 0.00737476 0.00409407 0.131477 +EDGE3 1480 1481 -0.868566 11.0486 -0.119752 0.0054756 -0.0250801 0.0815931 +EDGE3 1483 1484 -0.812379 11.29 -0.0191434 0.0176504 0.0335709 0.11927 +EDGE3 1482 1483 -0.716695 11.1946 -0.0739413 -0.00692351 0.00072719 0.141028 +EDGE3 1485 1486 -0.651917 11.2907 -0.187375 0.0185111 -0.0035518 0.116695 +EDGE3 1484 1485 -0.767046 10.9699 -0.254401 0.00831831 -0.0164869 0.117487 +EDGE3 1487 1488 -0.726768 11.1517 -0.185653 0.0268055 0.0235779 0.134298 +EDGE3 1486 1487 -0.846506 11.1812 -0.194739 0.0232121 0.0376882 0.077808 +EDGE3 1489 1490 -0.949679 11.0637 -0.228917 -0.0461066 -0.00232072 0.112125 +EDGE3 1488 1489 -0.575267 11.0809 -0.0881461 -0.000161423 0.0135956 0.162035 +EDGE3 1491 1492 -0.696829 11.1188 -0.127157 -0.0133798 0.00458376 0.101004 +EDGE3 1490 1491 -0.651701 10.8896 -0.111338 -0.0101202 0.016122 0.107558 +EDGE3 1493 1494 -0.629951 10.8582 -0.125346 -0.0258668 -0.0265167 0.128707 +EDGE3 1492 1493 -0.86919 10.9333 -0.107071 -0.0139128 0.0451828 0.154112 +EDGE3 1495 1496 -0.858548 10.9579 -0.197242 -0.00159841 -0.000965489 0.186342 +EDGE3 1494 1495 -0.698575 10.8827 -0.188322 0.0120596 -0.0145786 0.112334 +EDGE3 1496 1497 -0.890954 10.955 -0.231359 -0.000837553 0.0107415 0.108104 +EDGE3 1497 1498 -0.657766 10.9258 -0.135147 -0.000398218 0.00433947 0.114692 +EDGE3 1499 1500 -0.818764 10.955 -0.152322 0.0183064 0.0471909 0.15569 +EDGE3 1498 1499 -0.769315 10.907 -0.0488937 -0.0400005 -0.00414637 0.18452 +EDGE3 1501 1502 -0.690969 10.949 -0.0654607 -0.0300232 0.0282235 0.180199 +EDGE3 1500 1501 -0.812384 10.7363 2.62281e-05 -0.0287062 0.0118043 0.125751 +EDGE3 1503 1504 -0.913549 11.0041 -0.264661 -0.0326939 0.0105017 0.167743 +EDGE3 1502 1503 -0.634835 11.0925 -0.165126 0.00069321 -0.0290792 0.108394 +EDGE3 1505 1506 -0.858482 10.8079 -0.279851 -0.0113901 0.0101563 0.087233 +EDGE3 1504 1505 -0.754814 11.0131 -0.190758 0.0511133 0.0141315 0.135092 +EDGE3 1507 1508 -0.763786 10.8238 -0.139534 0.0098563 0.0551534 0.118198 +EDGE3 1506 1507 -0.78375 10.8728 -0.158525 -0.0433313 -0.0410103 0.118399 +EDGE3 1509 1510 -0.731288 11.1831 -0.585292 0.0281752 -0.00560898 0.116249 +EDGE3 1508 1509 -0.811729 10.8933 0.0176502 0.0272373 0.0333963 0.13345 +EDGE3 1511 1512 -0.545265 10.975 -0.28565 0.0601932 0.0296601 0.147667 +EDGE3 1510 1511 -0.70313 10.8141 -0.122002 -0.0289339 0.0140558 0.101257 +EDGE3 1513 1514 -0.645929 10.9226 -0.0627868 0.0151821 0.0240891 0.137027 +EDGE3 1512 1513 -0.623788 10.8109 -0.184549 -0.0108516 0.000160591 0.119949 +EDGE3 1515 1516 -0.766135 10.806 -0.0152587 -0.0116156 -0.0335572 0.106718 +EDGE3 1514 1515 -0.823034 10.9067 -0.126091 0.0215245 0.0322627 0.162977 +EDGE3 1517 1518 -0.82753 10.9038 -0.13801 0.0345412 -0.0347808 0.149708 +EDGE3 1516 1517 -0.77377 10.8021 -0.0526588 0.0181989 -0.0255275 0.146536 +EDGE3 1519 1520 -0.504773 11.0947 -0.0426348 -0.0260844 0.0114665 0.122245 +EDGE3 1518 1519 -0.800935 10.7977 -0.151099 0.0073104 -0.0217946 0.101813 +EDGE3 1521 1522 -0.814388 10.683 -0.0553387 -0.0301726 -0.0319639 0.0886656 +EDGE3 1520 1521 -0.750944 10.9378 -0.178184 0.0161717 -0.0274563 0.0853167 +EDGE3 1523 1524 -0.690492 10.8253 -0.243758 0.00327874 0.00341512 0.116672 +EDGE3 1522 1523 -0.752952 10.7956 -0.150516 -0.00794958 -0.0193869 0.134512 +EDGE3 1525 1526 -0.599542 10.7155 -0.174667 -0.00744494 0.00867748 0.150445 +EDGE3 1524 1525 -0.725211 10.7114 -0.181242 -0.0139456 0.0133567 0.107132 +EDGE3 1527 1528 -0.868936 10.8311 -0.0597591 -0.0253752 0.00329597 0.144883 +EDGE3 1526 1527 -0.845192 10.7503 -0.166406 -0.00940567 -0.00948667 0.129376 +EDGE3 1529 1530 -0.668843 10.493 -0.0887836 0.00320154 -0.00745328 0.101759 +EDGE3 1528 1529 -0.886508 10.8592 -0.0016041 0.0103112 -0.01435 0.0983258 +EDGE3 1531 1532 -0.799073 10.6665 -0.191071 0.00371089 0.0433023 0.114702 +EDGE3 1530 1531 -0.788502 10.7334 -0.0207101 0.0251228 -0.0309115 0.135584 +EDGE3 1533 1534 -0.805161 10.7776 0.0472833 0.00545121 0.0353866 0.136711 +EDGE3 1532 1533 -0.779409 10.7329 -0.0610058 -0.0763342 -0.00124007 0.114103 +EDGE3 1535 1536 -0.70088 10.775 -0.155415 -0.0248442 0.016121 0.134439 +EDGE3 1534 1535 -0.839707 10.8445 -0.0904785 0.0066291 -0.0338992 0.135829 +EDGE3 1537 1538 -0.591685 10.6795 -0.0166187 0.00715553 0.01674 0.134092 +EDGE3 1536 1537 -0.786647 10.5853 -0.0753195 0.0101503 -0.0348154 0.133204 +EDGE3 1539 1540 -0.720201 10.8424 -0.24334 0.0249414 0.00527282 0.137787 +EDGE3 1538 1539 -0.798068 10.4831 0.0648581 0.0181288 -0.0042326 0.0962613 +EDGE3 1541 1542 -0.565793 10.625 -0.151464 0.0282195 0.0246272 0.137461 +EDGE3 1540 1541 -0.640804 10.6849 -0.0834486 -0.00925988 0.0191227 0.144058 +EDGE3 1543 1544 -0.745627 10.717 -0.0892168 -0.0173037 0.00968544 0.0950442 +EDGE3 1542 1543 -0.665858 10.6288 -0.131034 -0.0072079 -0.0150632 0.108855 +EDGE3 1545 1546 -0.503655 10.5886 -0.159636 0.0303124 0.054497 0.149942 +EDGE3 1544 1545 -0.866148 10.6356 0.0157844 -0.0149982 0.00537119 0.11604 +EDGE3 1547 1548 -0.674165 10.4401 -0.198423 0.0115663 -0.00928917 0.129788 +EDGE3 1546 1547 -0.877123 10.591 -0.0863929 0.00905625 -0.0206582 0.121586 +EDGE3 1549 1550 -0.845812 10.4845 -0.266295 0.024116 0.0305419 0.13779 +EDGE3 1548 1549 -0.650655 10.541 0.0249421 0.0197304 -0.0374091 0.0944233 +EDGE3 1551 1552 -0.833972 10.5307 -0.185718 0.0189974 -0.0373438 0.124938 +EDGE3 1550 1551 -0.806666 10.5978 -0.0860458 -0.0590688 0.0372662 0.108483 +EDGE3 1553 1554 -0.70908 10.5389 -0.240168 -0.0143333 -0.0240184 0.15497 +EDGE3 1552 1553 -0.649057 10.859 -0.101642 0.00935434 0.0325665 0.0777964 +EDGE3 1555 1556 -0.637226 10.4245 -0.0111009 -0.0257128 0.0121119 0.178361 +EDGE3 1554 1555 -0.718854 10.6258 -0.000948513 0.0383765 0.0207531 0.164019 +EDGE3 1557 1558 -0.739799 10.4902 -0.0684403 -0.0132278 0.019566 0.105018 +EDGE3 1556 1557 -0.680336 10.499 -0.0801165 0.0245101 -0.0255263 0.0890899 +EDGE3 1559 1560 -0.605944 10.5713 -0.05904 -0.00943931 0.0213736 0.139103 +EDGE3 1558 1559 -0.955356 10.3799 -0.210076 0.00166901 0.0149256 0.130334 +EDGE3 1561 1562 -0.889502 10.3846 0.00874363 -0.0271694 -0.00251044 0.13106 +EDGE3 1560 1561 -0.64644 10.4547 0.100447 0.000289085 0.0228146 0.0560401 +EDGE3 1563 1564 -0.68361 10.4009 -0.0327574 -4.78827e-05 0.0209629 0.152052 +EDGE3 1562 1563 -0.934278 10.2971 -0.304762 -0.0180024 -0.00667622 0.133499 +EDGE3 1565 1566 -0.752588 10.3549 -0.0185723 -0.000520119 -0.0166283 0.141391 +EDGE3 1564 1565 -0.719816 10.2226 -0.095684 0.00248192 -0.00166925 0.160408 +EDGE3 1566 1567 -0.587131 10.4908 -0.249476 -0.0114429 -0.0305195 0.113804 +EDGE3 1567 1568 -0.877173 10.405 -0.0689086 -0.000821324 -0.016827 0.126927 +EDGE3 1569 1570 -0.553903 10.3833 0.0637206 0.00127865 -0.0371223 0.100478 +EDGE3 1568 1569 -0.757547 10.4845 -0.070405 -0.00480287 0.0337041 0.0919309 +EDGE3 1571 1572 -0.671897 10.5405 -0.12211 -0.00531599 0.0523828 0.142585 +EDGE3 1570 1571 -0.722669 10.2312 -0.181582 0.00460263 -0.00432729 0.137502 +EDGE3 1572 1573 -0.704374 10.3227 -0.114147 0.0129803 0.0218594 0.132708 +EDGE3 1573 1574 -0.897113 10.4688 -0.0730705 -0.0217608 0.0284533 0.140451 +EDGE3 1574 1575 -0.85006 10.3487 -0.156801 -0.00515724 0.00237515 0.143018 +EDGE3 1575 1576 -0.594273 10.413 -0.13624 -0.00249707 0.0031658 0.131444 +EDGE3 1576 1577 -0.873298 10.1833 0.0374786 0.0134838 -0.0151321 0.154252 +EDGE3 1577 1578 -0.789229 10.2971 -0.0196367 0.00657941 0.018792 0.109646 +EDGE3 1578 1579 -0.66171 10.3759 -0.103992 0.0178227 -0.016167 0.133814 +EDGE3 1579 1580 -0.711348 10.1878 -0.162254 0.00798455 0.0459019 0.139432 +EDGE3 1580 1581 -0.866341 10.4057 -0.1932 0.0198864 0.0259737 0.169639 +EDGE3 1581 1582 -0.704626 10.2825 -0.00461196 -0.0253643 0.0398469 0.135941 +EDGE3 1582 1583 -0.575311 10.3451 -0.204039 0.0024565 -0.0245127 0.111989 +EDGE3 1583 1584 -0.77396 10.311 -0.187003 -0.0118499 -0.00113107 0.1368 +EDGE3 1584 1585 -0.814996 10.2975 -0.163829 -0.0111298 0.0233787 0.113658 +EDGE3 1585 1586 -0.606138 10.2286 -0.217942 1.48502e-05 0.00684994 0.144967 +EDGE3 1586 1587 -0.789966 10.3835 -0.13967 -0.0378476 0.00189062 0.0977099 +EDGE3 1587 1588 -0.734098 10.2444 -0.091238 0.010668 -0.0202097 0.12683 +EDGE3 1588 1589 -0.643881 10.1186 -0.264428 -0.0239292 0.0133554 0.114543 +EDGE3 1589 1590 -0.574632 10.0996 -0.0175673 0.00189412 0.0205331 0.158711 +EDGE3 1590 1591 -0.832586 10.1173 -0.295389 0.00842653 -0.020139 0.148985 +EDGE3 1591 1592 -0.924837 10.2214 -0.180035 0.0128151 0.0056863 0.154282 +EDGE3 1592 1593 -0.54893 10.2235 -0.0904191 -0.0234473 0.0496487 0.107614 +EDGE3 1593 1594 -0.745669 10.1842 -0.115633 -0.0318602 0.00472356 0.167626 +EDGE3 1594 1595 -0.698573 10.2861 -0.0736418 0.0539673 -0.0193833 0.116712 +EDGE3 1595 1596 -0.620752 10.1322 -0.146062 0.0278095 0.00252667 0.102596 +EDGE3 1596 1597 -0.543616 10.2947 -0.283068 -0.023585 -0.000168661 0.197775 +EDGE3 1597 1598 -0.639174 10.0937 0.0609723 -0.0167607 -0.0659889 0.14698 +EDGE3 1598 1599 -0.702633 10.0605 -0.0391199 0.0100379 -0.00932702 0.136223 +EDGE3 1599 1600 -0.75894 10.0663 0.123634 0.0322061 0.00586886 0.117895 +EDGE3 1600 1601 -0.659198 10.105 0.0745058 -0.0297447 0.0547458 0.142817 +EDGE3 1601 1602 -0.687542 10.105 -0.375305 -0.00794135 0.000451448 0.14969 +EDGE3 1602 1603 -0.678793 10.1007 -0.105843 0.0107559 0.00372365 0.17195 +EDGE3 1603 1604 -0.821376 10.0977 0.064333 0.0313828 -0.0147148 0.152392 +EDGE3 1604 1605 -0.717183 9.95414 -0.170076 0.00364762 -0.0060896 0.119541 +EDGE3 1605 1606 -0.792106 10.1496 -0.211601 -0.00750109 0.032913 0.124917 +EDGE3 1606 1607 -0.864513 10.1466 -0.0198275 0.00693507 0.0125637 0.114364 +EDGE3 1607 1608 -0.73648 10.0324 -0.0849179 0.0159353 -0.00492891 0.147049 +EDGE3 1608 1609 -0.829717 10.0675 -0.126887 -0.026664 0.031747 0.0859422 +EDGE3 1609 1610 -0.824807 10.0256 -0.0601421 -0.0329291 0.00857567 0.108399 +EDGE3 1610 1611 -0.703937 10.129 -0.0209478 0.00626935 -0.0262067 0.175728 +EDGE3 1611 1612 -0.769169 9.9703 -0.155508 0.0272901 -0.00440823 0.151324 +EDGE3 1612 1613 -0.938286 9.88498 -0.165278 0.0267188 0.0151059 0.147732 +EDGE3 1613 1614 -0.80734 9.96917 -0.196437 0.0100816 -0.0360232 0.131929 +EDGE3 1614 1615 -0.777518 10.2014 -0.179278 0.0264011 -0.0120214 0.145467 +EDGE3 1615 1616 -0.703685 10.0412 -0.211756 0.00637657 -0.00935921 0.114022 +EDGE3 1616 1617 -0.88836 9.90036 -0.099825 -0.00813145 0.0161376 0.097188 +EDGE3 1617 1618 -0.724321 9.96978 -0.0210966 0.00751956 0.0287284 0.105586 +EDGE3 1618 1619 -0.552716 9.83963 -0.263627 -0.0423327 0.0290408 0.127647 +EDGE3 1619 1620 -0.70747 9.88663 -0.0861064 0.0148009 -0.0161281 0.133085 +EDGE3 1620 1621 -0.734189 9.66826 -0.0597107 -0.0256024 0.0460396 0.0652566 +EDGE3 1621 1622 -0.732204 9.81497 -0.280626 -0.00466485 -0.00484158 0.145787 +EDGE3 1622 1623 -0.746092 10.029 -0.119288 -0.0208656 -0.0225175 0.139583 +EDGE3 1623 1624 -0.73048 9.88919 -0.147405 0.00805315 0.0204661 0.128377 +EDGE3 1624 1625 -0.681575 9.96345 -0.00939034 -0.00809732 0.0137319 0.105381 +EDGE3 1625 1626 -0.757497 10.0876 -0.0535463 0.0373648 -0.0437511 0.144844 +EDGE3 1626 1627 -0.889859 10.1134 -0.194024 0.00604145 0.029758 0.117944 +EDGE3 1627 1628 -0.700483 9.90796 -0.177935 0.00266432 -0.000381426 0.120311 +EDGE3 1628 1629 -0.663937 9.87457 0.0213945 0.00704161 -0.023901 0.0931819 +EDGE3 1629 1630 -0.754584 9.92231 0.0864061 -0.0419924 0.0169616 0.115129 +EDGE3 1630 1631 -0.564508 9.88318 -0.304356 -0.0208714 0.0119623 0.115354 +EDGE3 1631 1632 -0.562155 9.62966 -0.170801 -0.0137264 -0.00591212 0.0923673 +EDGE3 1632 1633 -0.70906 9.89422 -0.159184 -0.0381354 0.00677309 0.0782353 +EDGE3 1633 1634 -0.708872 9.78846 -0.199598 -0.0161811 0.0233108 0.131592 +EDGE3 1634 1635 -0.63312 9.72897 0.17502 0.0354555 -0.0167249 0.138678 +EDGE3 1635 1636 -0.793904 9.72406 -0.134484 -0.000763664 0.00315353 0.125993 +EDGE3 1636 1637 -0.780034 9.78164 0.038766 0.00578832 0.00831429 0.144622 +EDGE3 1637 1638 -0.708446 9.82755 -0.105839 0.009442 0.0105601 0.124663 +EDGE3 1638 1639 -0.687722 9.66508 -0.0623805 0.0246893 -0.00952608 0.12762 +EDGE3 1639 1640 -0.626764 9.83257 -0.120097 -0.0093811 0.045762 0.146071 +EDGE3 1640 1641 -0.584435 9.68008 -0.0301858 -0.00217936 0.0158657 0.118887 +EDGE3 1641 1642 -0.595825 9.69538 -0.117311 0.0142343 0.00654262 0.139512 +EDGE3 1642 1643 -0.842967 9.74655 -0.124403 0.0261376 0.0342276 0.176946 +EDGE3 1643 1644 -0.656335 9.74766 0.12482 -0.0246025 -0.028557 0.118166 +EDGE3 1644 1645 -0.687351 9.60586 -0.314446 0.02515 -0.0176447 0.130441 +EDGE3 1645 1646 -0.67405 9.58808 -0.218654 0.0170867 -0.00520986 0.0898719 +EDGE3 1646 1647 -0.872089 9.83861 -0.209887 0.0245379 -0.0282538 0.134539 +EDGE3 1647 1648 -0.77804 9.75372 -0.167887 -0.0147619 0.0260108 0.119597 +EDGE3 1648 1649 -0.644343 9.70163 -0.0436996 0.00835036 0.0404947 0.120772 +EDGE3 1649 1650 -0.696945 9.51407 -0.166362 0.00904026 -0.00279738 0.164611 +EDGE3 1650 1651 -0.748223 9.6971 -0.0307378 -0.0122166 -0.0103572 0.175052 +EDGE3 1651 1652 -0.513724 9.57845 -0.1456 -0.0250517 0.00802307 0.0960922 +EDGE3 1652 1653 -0.698201 9.69768 0.0433684 0.0501978 0.012006 0.107207 +EDGE3 1653 1654 -0.647688 9.67397 0.146256 0.0159569 -0.0202746 0.155391 +EDGE3 1654 1655 -0.514112 9.52581 0.0412062 -0.034541 -0.018956 0.119738 +EDGE3 1655 1656 -0.744897 9.67447 -0.137684 0.050452 0.0255678 0.148118 +EDGE3 1656 1657 -0.650381 9.26115 -0.010917 -0.0600465 -0.0212044 0.148168 +EDGE3 1657 1658 -0.593845 9.55213 -0.0213887 -0.0493912 0.0217435 0.0842465 +EDGE3 1658 1659 -0.704211 9.42074 0.00739194 0.0015695 0.0514317 0.0865727 +EDGE3 1659 1660 -0.778782 9.5952 0.0433267 -0.00531216 0.0223656 0.12429 +EDGE3 1660 1661 -0.729748 9.56465 0.10144 -0.00557635 0.00579897 0.115577 +EDGE3 1661 1662 -0.635403 9.53393 -0.135975 -0.000707109 0.0233408 0.183467 +EDGE3 1662 1663 -0.57024 9.42204 0.028072 0.018783 -0.0180629 0.148946 +EDGE3 1663 1664 -0.568602 9.56169 -0.0348408 -0.00119566 -0.014026 0.118828 +EDGE3 1664 1665 -0.7148 9.41446 -0.0613961 0.076926 -0.00242408 0.161939 +EDGE3 1665 1666 -0.723319 9.48487 -0.0146073 0.0476083 0.0199671 0.137729 +EDGE3 1666 1667 -0.857875 9.41139 -0.0827327 -0.0222894 0.0159279 0.0669186 +EDGE3 1667 1668 -0.573171 9.57019 -0.233681 -0.00666988 -0.0110857 0.172771 +EDGE3 1668 1669 -0.744694 9.49026 -0.0710553 0.0101353 -0.0208969 0.112845 +EDGE3 1669 1670 -0.560253 9.49395 -0.213524 0.0178051 0.00769472 0.114583 +EDGE3 1670 1671 -0.809284 9.35543 -0.00558665 -0.0467412 -7.57943e-06 0.126381 +EDGE3 1671 1672 -0.46807 9.67677 -0.317399 -0.00225475 -0.00185606 0.101114 +EDGE3 1672 1673 -0.556198 9.42756 -0.184035 -0.0163652 0.0158387 0.166884 +EDGE3 1673 1674 -0.785348 9.46187 -0.0683788 -0.0267214 0.0020553 0.1076 +EDGE3 1674 1675 -0.568183 9.34009 -0.0366307 -0.0519397 0.0122884 0.0945701 +EDGE3 1675 1676 -0.722784 9.39659 -0.156157 0.0449734 0.0230453 0.148599 +EDGE3 1676 1677 -0.663429 9.36498 -0.317055 0.00321725 -0.00578545 0.119963 +EDGE3 1677 1678 -0.643589 9.45744 -0.000340064 0.0370378 0.00576772 0.128112 +EDGE3 1678 1679 -0.678352 9.38289 -0.282192 0.0206799 0.0101582 0.115906 +EDGE3 1679 1680 -0.749277 9.22989 -0.283966 0.0203346 0.0176743 0.0889679 +EDGE3 1680 1681 -0.735439 9.33041 -0.257581 0.0118447 -0.0108115 0.126129 +EDGE3 1681 1682 -0.686815 9.35258 0.0409327 -0.0259937 -0.0602435 0.120302 +EDGE3 1682 1683 -0.705145 9.22934 -0.127375 0.00848075 -0.0120483 0.0917773 +EDGE3 1683 1684 -0.712508 9.3165 -0.0796427 -0.0178537 0.00453738 0.140811 +EDGE3 1684 1685 -0.545364 9.37687 0.10263 -0.0010473 0.00275426 0.0851827 +EDGE3 1685 1686 -0.579159 9.34232 -0.0576823 -0.000358068 -0.0196 0.129116 +EDGE3 1686 1687 -0.808803 9.315 -0.0674509 -0.0268298 -0.00401599 0.103319 +EDGE3 1687 1688 -0.759367 9.15696 0.182457 0.0344086 -0.0242115 0.162364 +EDGE3 1688 1689 -0.717845 9.41303 -0.189579 -0.0200928 -0.0472496 0.117321 +EDGE3 1689 1690 -0.774564 9.29599 -0.0396722 -0.0525672 0.0453419 0.124735 +EDGE3 1690 1691 -0.720963 9.32326 -0.198101 0.00714728 0.00557752 0.127224 +EDGE3 1691 1692 -0.602951 9.35424 -0.0303865 0.0419929 -0.0131379 0.146085 +EDGE3 1692 1693 -0.93931 8.91467 -0.128691 -0.0160606 -0.0201286 0.139829 +EDGE3 1693 1694 -0.688711 9.29549 -0.0398784 0.0309624 -0.035245 0.110457 +EDGE3 1694 1695 -0.712653 9.03587 0.00547407 -0.0154061 -0.0288973 0.0895659 +EDGE3 1695 1696 -0.781559 9.19843 -0.0417933 -0.00220844 -0.00856946 0.0717394 +EDGE3 1696 1697 -0.693671 9.23885 -0.205869 0.000304972 -0.015721 0.107157 +EDGE3 1697 1698 -0.779164 9.12891 -0.131712 -0.0238033 -0.00653049 0.0969046 +EDGE3 1698 1699 -0.516838 9.12342 -0.109469 0.0326453 -0.000856792 0.154649 +EDGE3 1699 1700 -0.814797 9.33593 -0.01895 0.026248 0.0504155 0.107485 +EDGE3 1700 1701 -0.682209 9.06116 -0.162985 -0.00312337 0.00409629 0.134856 +EDGE3 1701 1702 -0.561639 8.96407 -0.194499 -0.0286583 0.0575284 0.126905 +EDGE3 1702 1703 -0.592798 9.13809 -0.110837 0.0304426 -0.0681029 0.165322 +EDGE3 1703 1704 -0.560217 9.19852 -0.156208 0.0584248 0.010993 0.147009 +EDGE3 1704 1705 -0.75988 9.1467 -0.0255926 0.000584789 0.00163579 0.128592 +EDGE3 1705 1706 -0.780831 9.18134 -0.157225 -0.0117138 -0.0213192 0.142391 +EDGE3 1706 1707 -0.474108 9.09002 -0.22295 -0.0322755 -0.00176778 0.126078 +EDGE3 1707 1708 -0.552497 9.07047 -0.0288139 -0.00367801 0.00155875 0.124782 +EDGE3 1708 1709 -0.676401 9.05583 -0.386603 -0.00563702 0.0113754 0.151259 +EDGE3 1709 1710 -0.807525 9.10391 -0.0761 0.029222 0.00570347 0.113883 +EDGE3 1710 1711 -0.625976 8.86045 -0.202683 0.00441529 -0.0190318 0.118447 +EDGE3 1711 1712 -0.776971 8.95951 -0.0657595 -0.00115974 -0.0097228 0.0992452 +EDGE3 1712 1713 -0.674098 9.10612 -0.0192329 -0.0201587 -0.0303272 0.114536 +EDGE3 1713 1714 -0.62253 9.00068 -0.0497596 -0.0132215 0.0208661 0.0923799 +EDGE3 1714 1715 -0.849589 9.15427 -0.21847 -0.00288796 -0.01632 0.156287 +EDGE3 1715 1716 -0.560842 8.93406 0.0711721 -0.0240781 0.0131156 0.146082 +EDGE3 1716 1717 -0.632669 8.91991 -0.248108 0.00918403 0.0108692 0.114394 +EDGE3 1717 1718 -0.750974 8.91528 -0.204321 -0.0289998 0.0147743 0.0788022 +EDGE3 1718 1719 -0.640254 8.9575 -0.203921 -0.0111372 0.0139786 0.11519 +EDGE3 1719 1720 -0.677173 8.85533 -0.145493 0.0120212 0.0477844 0.111859 +EDGE3 1720 1721 -0.767934 8.83573 -0.10138 0.00674059 0.0246641 0.126807 +EDGE3 1722 1723 -0.736755 8.94689 -0.117932 -0.00254839 -0.0206319 0.184527 +EDGE3 1721 1722 -0.648896 8.90637 -0.0896637 0.0172373 0.00616958 0.1126 +EDGE3 1724 1725 -0.669399 8.7364 -0.250348 -0.0202047 0.0332804 0.126648 +EDGE3 1723 1724 -0.706499 8.75531 -0.164559 0.0120312 -0.00135698 0.186484 +EDGE3 1726 1727 -0.655875 8.72136 -0.145399 -0.0110006 0.0400038 0.12634 +EDGE3 1725 1726 -0.741493 8.75915 -0.0164839 0.0129082 -0.05129 0.104809 +EDGE3 1728 1729 -0.777844 8.86409 -0.167866 -0.0168468 0.0477061 0.103469 +EDGE3 1727 1728 -0.828755 8.72127 -0.217803 -0.00197419 -0.0147115 0.131111 +EDGE3 1730 1731 -0.585116 8.9135 -0.0729074 0.0185185 -0.026955 0.112559 +EDGE3 1729 1730 -0.579206 9.04998 -0.0741514 -0.0256319 0.00589723 0.153035 +EDGE3 1732 1733 -0.603184 8.73013 -0.137046 -0.0481282 0.0256601 0.12502 +EDGE3 1731 1732 -0.494768 8.73032 -0.186201 0.00773131 0.000734901 0.129756 +EDGE3 1734 1735 -0.659853 8.82085 -0.258604 -0.0102844 0.0196813 0.141938 +EDGE3 1733 1734 -0.774192 8.69864 0.0306604 0.0375445 0.0135582 0.124304 +EDGE3 1736 1737 -0.678966 8.68085 -0.199623 0.0162647 0.0035466 0.13546 +EDGE3 1735 1736 -0.752781 8.75014 -0.184129 -0.000646369 -0.0479652 0.160016 +EDGE3 1738 1739 -0.645147 8.82355 0.036166 -0.0218937 -0.00889489 0.160658 +EDGE3 1737 1738 -0.430789 8.95105 -0.203691 0.0127907 -0.0461139 0.125903 +EDGE3 1740 1741 -0.694621 8.646 -0.103002 -0.0270463 0.0405312 0.171305 +EDGE3 1739 1740 -0.662647 8.53992 -0.0333173 -0.00335517 -0.0170043 0.127648 +EDGE3 1742 1743 -0.584646 8.76157 -0.0163477 -0.00883968 0.000192248 0.0951631 +EDGE3 1741 1742 -0.708331 8.81685 -0.108245 0.0126437 -0.0308474 0.0894812 +EDGE3 1743 1744 -0.709631 8.62351 -0.0321975 0.000188318 0.0452064 0.0921412 +EDGE3 1744 1745 -0.786989 8.76276 -0.0835905 0.00511522 0.00937952 0.144446 +EDGE3 1746 1747 -0.70017 8.73094 -0.123239 0.0311117 0.00875913 0.159535 +EDGE3 1745 1746 -0.576809 8.5749 -0.184519 0.00906226 0.000989937 0.101131 +EDGE3 1748 1749 -0.388173 8.49807 -0.0683552 0.00145625 0.00107192 0.157595 +EDGE3 1747 1748 -0.596757 8.68158 -0.182011 0.0267092 -0.0229518 0.0984165 +EDGE3 1750 1751 -0.803654 8.40349 -0.0437228 0.000261433 -0.0159064 0.183327 +EDGE3 1749 1750 -0.485232 8.48924 -0.114901 -0.00303902 -0.0156962 0.118598 +EDGE3 1752 1753 -0.58819 8.34542 -0.0900196 0.0292324 -0.00916929 0.101214 +EDGE3 1751 1752 -0.677485 8.74875 -0.0597782 -0.0527454 0.00858423 0.11597 +EDGE3 1754 1755 -0.667748 8.63223 -0.153379 -0.0168325 -0.00679313 0.105471 +EDGE3 1753 1754 -0.624866 8.60142 -0.10477 -0.0343928 -0.0140979 0.115482 +EDGE3 1756 1757 -0.712165 8.43949 -0.151737 -0.0254416 -0.0368607 0.124393 +EDGE3 1755 1756 -0.306251 8.50136 -0.152428 0.0306043 -0.00736677 0.138076 +EDGE3 1758 1759 -0.70848 8.48636 -0.0536761 0.0639316 0.00182 0.114804 +EDGE3 1757 1758 -0.422942 8.27454 -0.198104 -0.00680361 0.0172089 0.120451 +EDGE3 1760 1761 -0.71823 8.47413 -0.146248 0.0309916 0.00236926 0.0728556 +EDGE3 1759 1760 -0.599689 8.43768 0.0314285 0.0272454 -0.00578223 0.125805 +EDGE3 1762 1763 -0.814696 8.39753 0.206215 -0.0397832 -0.000219592 0.178783 +EDGE3 1761 1762 -0.707567 8.44297 -0.148556 -0.0267319 -0.036005 0.156107 +EDGE3 1764 1765 -0.536458 8.25601 0.0306788 0.0257825 0.0173608 0.123464 +EDGE3 1763 1764 -0.660847 8.37624 -0.0128089 -0.00955636 0.00828518 0.111864 +EDGE3 1765 1766 -0.705058 8.50952 -0.0684241 -0.00200543 -0.00117036 0.115512 +EDGE3 1766 1767 -0.565805 8.4194 -0.0928328 0.0479989 0.0216385 0.164741 +EDGE3 1767 1768 -0.723391 8.48469 -0.128015 0.0271598 0.0112233 0.123839 +EDGE3 1769 1770 -0.690778 8.38054 -0.0710786 0.0228547 -0.00504621 0.164824 +EDGE3 1768 1769 -0.65917 8.40844 -0.118198 0.0219117 -0.00948477 0.117545 +EDGE3 1771 1772 -0.668571 8.22355 -0.151659 0.0258845 -0.00916531 0.125334 +EDGE3 1770 1771 -0.646399 8.32393 -0.0479328 -0.0291056 -0.0511223 0.118658 +EDGE3 1773 1774 -0.598979 8.38568 -0.149155 0.00278584 0.00836642 0.0615321 +EDGE3 1772 1773 -0.75194 8.32408 -0.0970834 0.0240853 0.0200909 0.116664 +EDGE3 1775 1776 -0.809922 8.27049 -0.0143896 0.0264685 0.00840505 0.122448 +EDGE3 1774 1775 -0.779119 8.30466 -0.119626 0.0100166 0.0304653 0.150759 +EDGE3 1777 1778 -0.746655 8.15559 -0.131233 0.0207767 -0.00230481 0.159991 +EDGE3 1776 1777 -0.593338 8.25504 -0.109116 0.0209401 0.0172667 0.0994542 +EDGE3 1779 1780 -0.699635 8.30135 -0.188942 0.00125318 0.0110711 0.0759287 +EDGE3 1778 1779 -0.677233 8.2617 -0.0430685 0.00261889 0.00397712 0.126189 +EDGE3 1781 1782 -0.531911 8.32118 -0.108374 -0.0456388 -0.0457196 0.145503 +EDGE3 1780 1781 -0.356799 8.08 0.179814 0.0175428 0.0133354 0.105841 +EDGE3 1783 1784 -0.702485 8.28048 -0.236952 0.032631 0.0132036 0.121639 +EDGE3 1782 1783 -0.517194 8.3647 -0.0816039 -0.0113316 -0.00935498 0.123588 +EDGE3 1785 1786 -0.657038 8.28114 -0.076788 -0.0267116 -0.0276254 0.12593 +EDGE3 1784 1785 -0.530726 8.05879 0.0280617 0.0283196 -0.00223296 0.147409 +EDGE3 1787 1788 -0.625021 8.21201 -0.169548 0.00359036 0.0282426 0.156112 +EDGE3 1786 1787 -0.606124 8.09641 -0.118244 -0.0174261 0.0108715 0.0779915 +EDGE3 1789 1790 -0.637342 7.97393 0.0176927 0.0125417 0.00602878 0.117514 +EDGE3 1788 1789 -0.603221 8.15783 0.0131202 0.0135851 -0.0300718 0.0887418 +EDGE3 1791 1792 -0.4675 8.10172 -0.227874 -0.0202107 -0.00505762 0.187154 +EDGE3 1790 1791 -0.642156 8.49444 -0.00505507 0.0155492 0.00667434 0.212576 +EDGE3 1793 1794 -0.692717 7.97644 -0.218317 0.0412772 -0.0190072 0.111222 +EDGE3 1792 1793 -0.583262 8.24003 -0.0586081 -0.0106597 0.0192138 0.118053 +EDGE3 1795 1796 -0.701217 8.11458 -0.19062 -0.0131211 0.0212533 0.172709 +EDGE3 1794 1795 -0.50726 7.94177 -0.0550599 0.0132374 0.00381553 0.156416 +EDGE3 1797 1798 -0.638789 7.85882 -0.0404762 -4.81768e-05 -0.00715674 0.114194 +EDGE3 1796 1797 -0.583463 8.05999 0.0603924 -0.0135708 -0.00240073 0.148866 +EDGE3 1798 1799 -0.502956 8.00445 0.128703 -0.0133184 -0.0154281 0.142503 +EDGE3 1799 1800 -0.350681 7.98474 -0.168339 0.0162657 -0.00395115 0.123277 +EDGE3 1801 1802 -0.489703 7.88749 -0.16153 -0.0185827 0.0243479 0.10266 +EDGE3 1800 1801 -0.586369 8.12125 0.025178 -0.0105243 0.00561974 0.14307 +EDGE3 1803 1804 -0.738894 7.96495 -0.00044407 -0.00714149 0.0163517 0.136468 +EDGE3 1802 1803 -0.777747 8.04265 0.00208033 -0.0169064 0.0325872 0.0884066 +EDGE3 1805 1806 -0.518517 8.02274 -0.156522 0.0140339 0.0517636 0.114445 +EDGE3 1804 1805 -0.561816 7.95631 -0.0495785 0.021295 -0.0075046 0.0951483 +EDGE3 1807 1808 -0.481337 7.82601 -0.108736 -0.02562 -0.0247567 0.117765 +EDGE3 1806 1807 -0.760717 7.83769 -0.21828 0.0277379 0.00369227 0.139079 +EDGE3 1809 1810 -0.54389 7.61162 -0.0275404 -0.0113437 0.000628877 0.137917 +EDGE3 1808 1809 -0.608133 7.99125 -0.0130481 0.0066436 -0.0250742 0.107451 +EDGE3 1811 1812 -0.495784 7.90348 -0.249235 0.00844911 -0.00503745 0.118693 +EDGE3 1810 1811 -0.59716 7.90639 0.0469827 -0.0143403 -0.0180821 0.154239 +EDGE3 1813 1814 -0.388583 7.87127 -0.201358 0.0201414 -0.020978 0.121156 +EDGE3 1812 1813 -0.656688 7.99965 0.0895815 0.00689396 0.00956668 0.125024 +EDGE3 1815 1816 -0.628084 7.83523 -0.15015 0.00235578 -0.0286318 0.114708 +EDGE3 1814 1815 -0.622409 7.73601 0.0454894 0.00971084 0.0263658 0.135219 +EDGE3 1817 1818 -0.752244 7.85653 0.219354 -0.0110083 0.00080948 0.121152 +EDGE3 1816 1817 -0.613556 7.90055 -0.135437 0.0419799 0.0116236 0.154949 +EDGE3 1819 1820 -0.557105 7.88868 -0.0568595 -0.000570752 -0.0251284 0.144818 +EDGE3 1818 1819 -0.444548 7.65223 -0.0622384 0.0220599 0.0123457 0.142817 +EDGE3 1820 1821 -0.558478 7.77024 -0.154082 -0.0379633 -0.0458024 0.115681 +EDGE3 1821 1822 -0.552669 7.60146 -0.149529 -0.0335837 -0.00866322 0.12301 +EDGE3 1823 1824 -0.479236 7.74255 -0.0890336 0.0317214 0.0231099 0.138777 +EDGE3 1822 1823 -0.497872 7.68574 0.0731087 -0.0229599 0.0139356 0.140911 +EDGE3 1825 1826 -0.643607 7.70309 -0.151663 0.022961 -0.0264489 0.12192 +EDGE3 1824 1825 -0.66249 7.67649 -0.280377 0.0428323 0.0103799 0.0938533 +EDGE3 1827 1828 -0.454281 7.62164 -0.0463409 0.0252649 0.00227443 0.132087 +EDGE3 1826 1827 -0.561888 7.63463 0.0813791 0.0482654 0.036408 0.119062 +EDGE3 1829 1830 -0.486236 7.71437 -0.0874024 0.0133049 0.0269794 0.0979645 +EDGE3 1828 1829 -0.616636 7.6669 -0.0283236 0.00132114 -0.0330184 0.0576458 +EDGE3 1831 1832 -0.503936 7.46525 0.0265229 -0.049481 -0.00662286 0.101659 +EDGE3 1830 1831 -0.544641 7.70487 -0.0302348 0.00968046 0.0214385 0.129918 +EDGE3 1833 1834 -0.369273 7.65201 -0.147934 0.00180613 0.00814367 0.141954 +EDGE3 1832 1833 -0.612607 7.65591 0.000338277 0.0477223 0.0144674 0.116775 +EDGE3 1835 1836 -0.725499 7.63309 -0.0695771 0.0200752 -0.0240662 0.11843 +EDGE3 1834 1835 -0.710925 7.63661 -0.12204 -0.0177994 0.0460849 0.0986058 +EDGE3 1837 1838 -0.484545 7.3979 -0.0843257 0.0393262 -0.0135392 0.119364 +EDGE3 1836 1837 -0.76968 7.60858 -0.055365 -0.0261081 -0.0347166 0.111402 +EDGE3 1839 1840 -0.596747 7.58721 -0.160864 0.00423862 0.00205655 0.117602 +EDGE3 1838 1839 -0.676206 7.57469 -0.127567 0.0205093 -0.00760563 0.119678 +EDGE3 1840 1841 -0.540566 7.37722 -0.0365421 -0.0137144 -0.0236966 0.119016 +EDGE3 1841 1842 -0.56783 7.57108 -0.0170808 -0.00517779 -0.0323436 0.100381 +EDGE3 1842 1843 -0.816632 7.37883 -0.242684 -0.00891008 -0.0019314 0.14686 +EDGE3 1843 1844 -0.574793 7.39348 0.000207881 -0.0149629 0.0187528 0.128942 +EDGE3 1844 1845 -0.639812 7.52313 -0.0712206 -0.00746899 0.0135401 0.126963 +EDGE3 1845 1846 -0.516564 7.4524 -0.109927 -0.00617191 0.019503 0.144732 +EDGE3 1846 1847 -0.602926 7.43068 0.080351 0.0259564 -0.00846394 0.156553 +EDGE3 1847 1848 -0.744843 7.36491 -0.118338 -0.0152024 -0.00463471 0.115466 +EDGE3 1848 1849 -0.784863 7.27879 0.0796544 0.00714721 0.0256237 0.142206 +EDGE3 1849 1850 -0.790865 7.40565 -0.188289 -0.0350114 -0.00988119 0.145072 +EDGE3 1850 1851 -0.824957 7.36214 -0.126318 0.0285922 0.0149701 0.137677 +EDGE3 1851 1852 -0.697343 7.46488 -0.334852 0.00578286 -0.022918 0.137522 +EDGE3 1852 1853 -0.491588 7.14689 0.0288469 0.0148793 0.0028611 0.100779 +EDGE3 1853 1854 -0.492023 7.21562 -0.276767 -0.0264316 0.0274543 0.0795735 +EDGE3 1854 1855 -0.492999 7.37041 -0.0204402 -0.0153191 -0.00818353 0.139639 +EDGE3 1855 1856 -0.583586 7.28588 0.0692816 0.0482741 -0.00975336 0.173601 +EDGE3 1856 1857 -0.542649 7.19335 -0.055555 -0.0226198 0.0181123 0.153751 +EDGE3 1857 1858 -0.458883 7.154 -0.0709714 0.0149913 -0.0105976 0.0927687 +EDGE3 1858 1859 -0.708149 7.28573 -0.0596832 -0.0304885 -0.0132937 0.166873 +EDGE3 1859 1860 -0.469572 7.17958 0.0603819 0.00101145 0.0238537 0.140439 +EDGE3 1860 1861 -0.712995 7.37549 -0.0023453 0.0590481 -0.00796288 0.113657 +EDGE3 1861 1862 -0.695822 7.20255 -0.0793183 -0.0146376 0.0407952 0.148829 +EDGE3 1862 1863 -0.653343 7.10013 0.0480446 -0.00649662 0.00155642 0.0774294 +EDGE3 1863 1864 -0.421038 7.31658 0.0464421 -0.0429812 0.00391796 0.0835818 +EDGE3 1864 1865 -0.482741 7.21506 -0.145924 -0.0117366 -0.0502524 0.134296 +EDGE3 1865 1866 -0.462875 7.16726 -0.0646054 0.0229863 0.023502 0.107869 +EDGE3 1866 1867 -0.550954 7.12792 -0.00313669 0.0248844 -0.00718612 0.142472 +EDGE3 1867 1868 -0.627023 7.11465 0.183613 -0.0307109 -0.0131778 0.114119 +EDGE3 1868 1869 -0.566914 7.02341 -0.0171478 0.0715752 -0.00772276 0.111022 +EDGE3 1869 1870 -0.540516 7.0914 -0.200393 0.0164244 0.00535865 0.157917 +EDGE3 1870 1871 -0.598124 7.03068 -0.10254 0.00742962 -0.0159418 0.136031 +EDGE3 1871 1872 -0.529143 7.02926 -0.0606631 0.0496358 -0.000917296 0.137647 +EDGE3 1872 1873 -0.678895 7.0873 0.0317984 -0.0391698 0.0391945 0.128879 +EDGE3 1873 1874 -0.610457 7.08198 -0.157537 -0.0356447 -0.0123137 0.112108 +EDGE3 1874 1875 -0.411361 6.88049 0.0822774 0.0365559 -0.0248319 0.133273 +EDGE3 1875 1876 -0.483482 6.99332 -0.0991983 -0.0194078 0.0178814 0.145435 +EDGE3 1876 1877 -0.748537 7.05946 -0.185719 -0.0121376 -0.0249354 0.146576 +EDGE3 1877 1878 -0.44977 6.93113 -0.10735 -0.00825561 -0.00445305 0.159435 +EDGE3 1878 1879 -0.64854 6.98633 -0.171388 -0.0259558 -0.0057098 0.090701 +EDGE3 1879 1880 -0.733591 6.83706 -0.156914 0.0111935 0.0702085 0.104652 +EDGE3 1880 1881 -0.72918 7.05224 -0.042273 -0.0248102 0.0110796 0.150161 +EDGE3 1881 1882 -0.526627 6.86658 -0.243012 -0.0459226 0.0136922 0.101599 +EDGE3 1882 1883 -0.421446 6.93485 -0.160414 0.0227686 0.027115 0.129951 +EDGE3 1883 1884 -0.696787 7.05659 -0.0109707 0.0110354 -0.0158986 0.135579 +EDGE3 1884 1885 -0.540851 6.91019 -0.260604 -0.00144137 0.00926761 0.18409 +EDGE3 1885 1886 -0.257752 6.95582 -0.285759 0.0277204 0.017442 0.0912489 +EDGE3 1886 1887 -0.497657 6.69758 -0.10556 -0.00206537 -0.0379426 0.16344 +EDGE3 1887 1888 -0.641877 6.63517 -0.113503 0.0142757 0.00465219 0.152178 +EDGE3 1888 1889 -0.690905 6.90573 -0.049073 -0.010793 0.0515383 0.144111 +EDGE3 1889 1890 -0.578388 6.85599 -0.119272 0.00912032 0.0225459 0.132499 +EDGE3 1890 1891 -0.412337 6.94012 -0.0196423 -0.0085138 -0.0125884 0.109291 +EDGE3 1891 1892 -0.368362 6.84904 -0.0792601 -0.0209925 0.0073428 0.129688 +EDGE3 1892 1893 -0.516569 6.94656 0.0711192 -0.0097681 0.00523245 0.12667 +EDGE3 1893 1894 -0.567491 6.79457 -0.332485 -0.0024642 0.0298564 0.135783 +EDGE3 1894 1895 -0.479747 6.78196 -0.156684 0.00724659 0.00412863 0.1236 +EDGE3 1895 1896 -0.404523 6.8344 -0.00829495 0.00329313 0.0337603 0.128635 +EDGE3 1896 1897 -0.449896 6.82615 -0.122386 0.0658244 0.023348 0.161592 +EDGE3 1897 1898 -0.629848 6.52678 -0.1765 -0.0312836 0.0150351 0.157928 +EDGE3 1898 1899 -0.721029 6.59479 -0.0018331 -0.041782 -0.0101293 0.104508 +EDGE3 1899 1900 -0.482961 6.6938 -0.141305 -0.0107854 0.00633317 0.145487 +EDGE3 1900 1901 -0.636508 6.7001 -0.176703 0.0176969 0.0449217 0.130211 +EDGE3 1901 1902 -0.521729 6.69379 0.0221292 0.0118396 -0.0175751 0.121839 +EDGE3 1902 1903 -0.599245 6.55218 -0.160692 -0.0171311 -0.0256619 0.138851 +EDGE3 1903 1904 -0.602417 6.6389 -0.280088 0.00411982 -0.0034784 0.187328 +EDGE3 1904 1905 -0.405013 6.69431 -0.0213429 0.0125513 0.0178674 0.121182 +EDGE3 1905 1906 -0.673734 6.69019 -0.154756 0.0361362 -0.0245292 0.127328 +EDGE3 1906 1907 -0.694768 6.65434 -0.0382554 -0.0163453 0.0108215 0.121861 +EDGE3 1907 1908 -0.582602 6.6863 -0.107225 -0.0174115 0.0219284 0.149327 +EDGE3 1908 1909 -0.529598 6.57438 -0.165611 0.037633 0.0251834 0.122439 +EDGE3 1909 1910 -0.550003 6.49588 -0.131708 0.0347732 0.00820918 0.146815 +EDGE3 1910 1911 -0.604966 6.55066 -0.0576862 -0.0300207 0.00607614 0.0536557 +EDGE3 1911 1912 -0.519194 6.48382 -0.000380502 0.022061 0.00674755 0.176131 +EDGE3 1912 1913 -0.58462 6.54622 0.112154 0.0235749 0.0118063 0.139007 +EDGE3 1913 1914 -0.617625 6.49059 -0.148337 0.00535814 -0.00172524 0.129453 +EDGE3 1914 1915 -0.479683 6.62715 -0.080135 -0.0178309 -0.00365513 0.0875597 +EDGE3 1915 1916 -0.58749 6.70822 0.0847443 -0.0305741 0.00754548 0.129222 +EDGE3 1916 1917 -0.451042 6.48218 -0.0207604 0.018108 0.0189387 0.117504 +EDGE3 1917 1918 -0.391254 6.60939 -0.173592 0.0496346 0.0202329 0.0947357 +EDGE3 1918 1919 -0.392004 6.42854 -0.047911 0.00284509 -0.0178553 0.12102 +EDGE3 1919 1920 -0.3076 6.52029 -0.00805391 0.00960978 -0.00877807 0.111829 +EDGE3 1920 1921 -0.482137 6.50725 0.0133788 0.0128875 -0.0255452 0.145842 +EDGE3 1921 1922 -0.422145 6.36038 -0.146317 -0.0380725 -0.00340331 0.128358 +EDGE3 1922 1923 -0.628684 6.32894 -0.155959 -0.000589319 -0.00927705 0.090458 +EDGE3 1923 1924 -0.489771 6.38105 -0.0216703 -0.0315264 0.00371578 0.140759 +EDGE3 1924 1925 -0.472106 6.34225 -0.20346 0.00230964 0.018118 0.1366 +EDGE3 1925 1926 -0.516094 6.42739 -0.129203 0.0551955 -0.0316826 0.125383 +EDGE3 1926 1927 -0.313683 6.38208 -0.050251 -0.0169743 0.0259984 0.0812736 +EDGE3 1927 1928 -0.477272 6.2889 -0.0326432 0.00185164 0.0239854 0.148875 +EDGE3 1928 1929 -0.457734 6.37111 -0.0477562 -0.0254784 -0.0154525 0.11644 +EDGE3 1929 1930 -0.50595 6.45736 -0.0867234 -0.0517454 -0.0307942 0.157101 +EDGE3 1930 1931 -0.647519 6.18865 -0.167554 0.0337091 0.00535225 0.131821 +EDGE3 1931 1932 -0.417839 6.3653 -0.191163 -0.0250263 0.0148571 0.131897 +EDGE3 1932 1933 -0.368519 6.39371 0.0628883 0.00944716 0.00232136 0.136309 +EDGE3 1933 1934 -0.407855 6.22758 -0.208137 -0.00569539 -0.00339384 0.152747 +EDGE3 1934 1935 -0.522082 6.06436 -0.00142494 -0.029872 -0.0185306 0.158903 +EDGE3 1935 1936 -0.549863 6.27677 -0.156211 -0.00563626 -0.0254933 0.143366 +EDGE3 1936 1937 -0.620376 6.10427 0.0152066 -0.00857525 -0.0180701 0.130078 +EDGE3 1937 1938 -0.470794 6.18691 0.0259853 0.00828865 0.0259791 0.130076 +EDGE3 1938 1939 -0.656877 6.23153 -0.100291 0.026037 0.0110495 0.0894652 +EDGE3 1939 1940 -0.635102 6.26215 -0.1812 0.0141179 0.00524722 0.124909 +EDGE3 1940 1941 -0.29092 6.22965 -0.0967064 -0.00883403 -0.019549 0.106338 +EDGE3 1941 1942 -0.589252 6.19792 0.0795378 0.00113142 0.00466372 0.159739 +EDGE3 1942 1943 -0.494553 6.07509 0.125068 0.0333908 0.0240146 0.068152 +EDGE3 1943 1944 -0.523077 6.14972 0.0384974 0.0279524 -0.0172954 0.119458 +EDGE3 1944 1945 -0.611566 6.08104 -0.037546 0.00407767 -0.0236275 0.11156 +EDGE3 1945 1946 -0.429217 6.02741 -0.180638 0.0141882 -0.00131638 0.181681 +EDGE3 1946 1947 -0.546358 6.22259 -0.0712174 -0.0239666 0.011451 0.115811 +EDGE3 1947 1948 -0.562523 6.13647 -0.0875678 -0.0105486 -0.00541187 0.122796 +EDGE3 1948 1949 -0.472512 6.15933 0.0987717 0.00384033 0.00405963 0.104676 +EDGE3 1949 1950 -0.475066 6.06233 -0.102596 0.0299962 0.0314837 0.0969954 +EDGE3 1950 1951 -0.511935 6.096 -0.220851 -0.0213939 -0.0033149 0.133139 +EDGE3 1951 1952 -0.381362 6.09181 0.0147118 0.0123153 0.0129928 0.116547 +EDGE3 1952 1953 -0.493175 6.04878 0.00131681 -0.0263127 -0.0282194 0.133053 +EDGE3 1953 1954 -0.47168 6.02958 -0.0846494 -0.0310142 -0.0065865 0.113841 +EDGE3 1954 1955 -0.275485 5.98738 0.0365826 0.0246277 0.0271227 0.124561 +EDGE3 1955 1956 -0.348478 5.86413 0.0151256 0.00602854 -0.0440739 0.0823114 +EDGE3 1956 1957 -0.584079 5.82886 -0.0905523 -0.0779055 -0.0115231 0.112895 +EDGE3 1957 1958 -0.510719 5.71333 0.0859423 0.0481265 -0.00488138 0.166338 +EDGE3 1958 1959 -0.433647 5.88994 -0.0425325 0.00630578 0.00902273 0.0885019 +EDGE3 1959 1960 -0.530816 5.86674 -0.0648881 -0.0063362 -0.0147436 0.129832 +EDGE3 1960 1961 -0.304594 5.77582 -0.113258 -0.0409613 0.00897089 0.135249 +EDGE3 1961 1962 -0.674556 5.83977 0.0558007 0.0200031 -0.0266717 0.104946 +EDGE3 1962 1963 -0.535759 5.90929 -0.040472 -0.0127562 -0.0306056 0.120575 +EDGE3 1963 1964 -0.217277 5.60784 -0.152631 0.0201969 -0.0422482 0.138303 +EDGE3 1964 1965 -0.543294 5.76971 0.091288 -0.0136055 0.0222789 0.143091 +EDGE3 1965 1966 -0.360085 5.80105 0.0883711 -0.0380865 0.0073375 0.102164 +EDGE3 1966 1967 -0.364984 5.81232 0.0157722 -0.0173888 0.0388329 0.0916746 +EDGE3 1967 1968 -0.486811 5.79092 -0.188699 0.012606 0.0375289 0.135605 +EDGE3 1968 1969 -0.464428 5.81241 -0.0374998 0.00117953 -0.00249678 0.132459 +EDGE3 1969 1970 -0.53232 5.52107 -0.0579246 -0.0457853 0.0192236 0.127546 +EDGE3 1970 1971 -0.390767 5.82101 -0.240988 0.00989655 0.000650397 0.140344 +EDGE3 1971 1972 -0.476969 5.77308 -0.00352681 0.00546006 0.00573579 0.133397 +EDGE3 1972 1973 -0.587015 5.76284 0.0642154 0.00948602 0.00942862 0.132311 +EDGE3 1973 1974 -0.585743 5.54748 -0.110048 0.0671397 -0.0149584 0.132186 +EDGE3 1974 1975 -0.428105 5.78837 -0.128039 -0.00878907 0.0170606 0.116039 +EDGE3 1975 1976 -0.52385 5.64427 -0.10341 -0.0367064 -0.0184896 0.146108 +EDGE3 1976 1977 -0.488289 5.50558 -0.326557 0.00112729 -0.0106616 0.0851344 +EDGE3 1977 1978 -0.482771 5.59547 0.0791137 0.0258674 0.0283043 0.120395 +EDGE3 1978 1979 -0.391061 5.71276 -0.0322463 -0.0414818 0.024244 0.139271 +EDGE3 1979 1980 -0.702794 5.62131 -0.176999 -0.0226085 -0.0162185 0.162242 +EDGE3 1980 1981 -0.4975 5.6404 0.199187 -0.0115058 0.0311392 0.124026 +EDGE3 1981 1982 -0.427967 5.61673 0.124204 -0.0177554 0.054869 0.0853869 +EDGE3 1982 1983 -0.410515 5.77818 0.0865397 0.00134919 0.0120908 0.124951 +EDGE3 1983 1984 -0.343418 5.69079 -0.208926 0.00737766 0.00820264 0.129788 +EDGE3 1984 1985 -0.524235 5.44817 -0.125203 0.0226284 0.0001204 0.100746 +EDGE3 1985 1986 -0.514837 5.45277 -0.0772258 -0.00204544 -0.0158974 0.0850198 +EDGE3 1986 1987 -0.401212 5.50711 -0.244434 0.0454171 0.0344975 0.134734 +EDGE3 1987 1988 -0.448047 5.60183 -0.0694431 0.0077945 0.00634264 0.114974 +EDGE3 1989 1990 -0.521532 5.51511 -0.203855 -0.0175875 -0.0356895 0.148315 +EDGE3 1988 1989 -0.447219 5.70468 -0.117758 -0.0254064 -0.0530245 0.103838 +EDGE3 1991 1992 -0.612525 5.37322 0.106326 -0.0349751 0.0235161 0.102388 +EDGE3 1990 1991 -0.526438 5.57083 -0.102111 -0.0259494 -0.0107402 0.101864 +EDGE3 1993 1994 -0.504727 5.32919 -0.0139626 -0.0265182 0.0154989 0.136552 +EDGE3 1992 1993 -0.366157 5.40521 -0.0683859 -0.0408997 0.0262 0.0864175 +EDGE3 1995 1996 -0.500908 5.36918 -0.00902292 0.00719876 -0.0325022 0.134315 +EDGE3 1994 1995 -0.515844 5.30031 -0.0592006 -0.00689442 -0.0143751 0.114798 +EDGE3 1997 1998 -0.583692 5.25541 -0.0275784 -0.00180304 -0.0030146 0.100445 +EDGE3 1996 1997 -0.34656 5.2351 -0.115611 0.049704 -0.0620094 0.111174 +EDGE3 1999 2000 -0.547622 5.28742 -0.0284439 0.00042945 0.010526 0.0914189 +EDGE3 1998 1999 -0.474041 5.5418 -0.145192 -0.0659393 0.00513539 0.125029 +EDGE3 2001 2002 -0.312809 5.23361 -0.044017 0.0287767 0.0156405 0.145694 +EDGE3 2000 2001 -0.572651 5.37553 -0.0311355 -0.0204672 -0.0165423 0.118667 +EDGE3 2003 2004 -0.46431 5.33129 0.162549 -0.041681 -0.00440007 0.109217 +EDGE3 2002 2003 -0.390939 5.2792 -0.0299605 0.0249188 0.00263654 0.0925308 +EDGE3 2005 2006 -0.599122 5.21584 -0.0843733 0.0220407 -0.00558616 0.122876 +EDGE3 2004 2005 -0.310875 5.31006 0.105366 0.00588317 -0.0475671 0.121278 +EDGE3 2007 2008 -0.606692 5.02984 0.0140732 -0.0333321 -0.0208616 0.146249 +EDGE3 2006 2007 -0.505119 5.31184 -0.00702885 0.0145621 0.0144722 0.121631 +EDGE3 2009 2010 -0.544477 5.11131 -0.0141051 0.00774711 0.0299208 0.148513 +EDGE3 2008 2009 -0.515179 5.17657 0.0106107 -0.0524172 0.0129831 0.135736 +EDGE3 2011 2012 -0.399633 5.14524 -0.118435 0.00562244 -0.00326332 0.100216 +EDGE3 2010 2011 -0.519642 5.05966 -0.137022 -0.0101053 -0.015811 0.122661 +EDGE3 2013 2014 -0.373308 5.21712 -0.0576836 -0.0147453 -0.0226989 0.120168 +EDGE3 2012 2013 -0.249265 4.96769 -0.125062 0.0115382 -0.00502312 0.139843 +EDGE3 2015 2016 -0.354819 5.14559 -0.0329543 0.0237119 -0.0426784 0.0853697 +EDGE3 2014 2015 -0.398446 5.09908 -0.112416 -0.0310785 -0.0146828 0.0966568 +EDGE3 2017 2018 -0.440011 5.24708 0.0875014 -0.00646356 -0.0276751 0.109471 +EDGE3 2016 2017 -0.416948 4.97894 -0.0427855 0.0201379 0.0183188 0.0877941 +EDGE3 2019 2020 -0.542174 5.01498 -0.24226 0.0191092 -0.0269399 0.10241 +EDGE3 2018 2019 -0.429374 5.18693 -0.104807 -0.0218478 0.0118937 0.0939241 +EDGE3 2021 2022 -0.433611 5.05696 0.0452068 0.0500272 0.00608865 0.150643 +EDGE3 2020 2021 -0.338687 4.89056 0.0779519 -0.0432755 -0.0424353 0.137962 +EDGE3 2023 2024 -0.580713 4.85174 -0.0214444 -0.00537442 0.0299923 0.0852498 +EDGE3 2022 2023 -0.329746 4.95757 -0.0850476 0.0356472 -0.0221145 0.142208 +EDGE3 2025 2026 -0.49215 5.0963 -0.0883497 0.000909229 -0.0241072 0.124497 +EDGE3 2024 2025 -0.475041 5.03223 -0.0614471 -0.00086757 0.00342266 0.119408 +EDGE3 2027 2028 -0.42349 5.09462 -0.0390856 -0.0112489 0.050239 0.143096 +EDGE3 2026 2027 -0.507461 5.09471 0.0658235 0.0113328 0.00183257 0.102365 +EDGE3 2029 2030 -0.583709 4.91967 -0.110588 -0.0552586 -0.0124483 0.133408 +EDGE3 2028 2029 -0.318981 4.76875 -0.00648015 0.00477891 0.0324749 0.0966385 +EDGE3 2031 2032 -0.260634 4.79268 -0.0325196 0.0184041 0.024755 0.142562 +EDGE3 2030 2031 -0.482101 4.70613 0.0417364 0.00891472 -0.0286942 0.15621 +EDGE3 2033 2034 -0.454825 4.94776 0.0465314 0.00351966 0.0344107 0.0988248 +EDGE3 2032 2033 -0.516957 4.90376 -0.172098 -0.00464732 0.0156243 0.112177 +EDGE3 2035 2036 -0.439556 4.66194 0.0489877 0.0301647 0.0428953 0.0902943 +EDGE3 2034 2035 -0.507534 4.97008 -0.118139 0.00837736 -0.0371207 0.110429 +EDGE3 2037 2038 -0.389706 4.69751 -0.134574 -0.0213516 0.00112269 0.130692 +EDGE3 2036 2037 -0.408103 4.9473 0.0216892 0.00115213 0.0146561 0.119241 +EDGE3 2039 2040 -0.395351 4.8987 -0.248401 -0.00267135 -0.00223908 0.127113 +EDGE3 2038 2039 -0.321593 4.73296 0.0884741 -0.005992 -0.0301676 0.119422 +EDGE3 2041 2042 -0.421757 4.60352 -0.0621156 -0.000916826 0.0034686 0.114247 +EDGE3 2040 2041 -0.358396 4.52372 0.0908028 0.0171255 -0.0142731 0.124731 +EDGE3 2043 2044 -0.338578 4.71598 0.0592084 -0.0124516 0.0345618 0.132249 +EDGE3 2042 2043 -0.523519 4.90062 -0.0526348 0.0368997 0.00527632 0.154218 +EDGE3 2045 2046 -0.221895 4.69512 -0.119361 0.03271 -0.0129443 0.121912 +EDGE3 2044 2045 -0.44992 4.83419 -0.0365695 0.00394512 -0.00914366 0.125644 +EDGE3 2047 2048 -0.438778 4.65677 -0.0303755 -0.0145647 -0.00145236 0.104334 +EDGE3 2046 2047 -0.382569 4.67905 0.0149483 -0.0228594 -0.0394021 0.139759 +EDGE3 2049 2050 -0.376983 4.62465 -0.112158 -0.00979766 -0.0110348 0.147876 +EDGE3 2048 2049 -0.428095 4.63229 -0.179287 0.0346308 -0.0323035 0.115618 +EDGE3 2051 2052 -0.255441 4.63863 -0.0455181 0.0085658 -0.000388081 0.122786 +EDGE3 2050 2051 -0.472955 4.63599 0.0639244 0.0186395 -0.0238679 0.121089 +EDGE3 2053 2054 -0.498458 4.33483 0.0329605 0.0358891 -0.00674524 0.146459 +EDGE3 2052 2053 -0.528183 4.54758 -0.148431 -0.0153674 -0.0285004 0.134527 +EDGE3 2055 2056 -0.223668 4.32295 0.00821725 0.00449827 0.00690212 0.134715 +EDGE3 2054 2055 -0.564532 4.57377 -0.212894 0.00721899 0.0418787 0.104927 +EDGE3 2057 2058 -0.399334 4.47999 0.0335685 0.00223499 -0.0456975 0.159375 +EDGE3 2056 2057 -0.331414 4.49365 -0.0418413 0.0409293 -0.00435209 0.0483188 +EDGE3 2059 2060 -0.312336 4.31939 -0.0300159 0.00506485 -0.000735401 0.0932429 +EDGE3 2058 2059 -0.495439 4.4803 0.0142532 -0.00829215 0.0139699 0.151718 +EDGE3 2060 2061 -0.373709 4.51656 -0.247001 -0.0099552 0.00739603 0.121673 +EDGE3 2061 2062 -0.303543 4.47449 -0.0822246 0.0203961 0.0196796 0.106226 +EDGE3 2063 2064 -0.478755 4.4357 -0.0258076 0.0051342 0.0296656 0.145708 +EDGE3 2062 2063 -0.286471 4.37132 0.0697163 -0.043802 -0.00528043 0.149795 +EDGE3 2065 2066 -0.255043 4.47359 -0.0718906 -0.0172138 -0.0246145 0.112685 +EDGE3 2064 2065 -0.36699 4.36082 -0.120507 -0.00213403 -0.00880765 0.111823 +EDGE3 2067 2068 -0.539926 4.25985 0.037346 -0.0221291 0.0348844 0.108918 +EDGE3 2066 2067 -0.659544 4.37798 -0.0812727 0.0299449 -0.0307418 0.125229 +EDGE3 2069 2070 -0.246703 4.4746 -0.0252056 -0.00916487 -0.0204101 0.0861235 +EDGE3 2068 2069 -0.388155 4.24081 0.0138345 -0.0247264 -0.00521176 0.150454 +EDGE3 2071 2072 -0.242405 4.25616 0.0571753 0.0202348 -0.0360929 0.108214 +EDGE3 2070 2071 -0.422488 4.37786 -0.126737 -0.00262252 -0.0126008 0.0880332 +EDGE3 2073 2074 -0.586037 4.3634 0.0255608 0.0136325 -0.00934094 0.147259 +EDGE3 2072 2073 -0.483544 4.24506 -0.0127363 -0.0174106 -0.0285645 0.138677 +EDGE3 2075 2076 -0.50635 4.24873 -0.187114 0.0363163 0.0270832 0.125179 +EDGE3 2074 2075 -0.329825 4.37637 -0.0571882 0.0540096 -0.0123013 0.122029 +EDGE3 2077 2078 -0.458412 4.20437 -0.104977 -0.00444973 -0.00653571 0.120028 +EDGE3 2076 2077 -0.480937 4.12185 0.032162 -0.00906752 -0.0252135 0.132499 +EDGE3 2079 2080 -0.368506 4.3189 -0.112995 -0.0121304 0.00932147 0.0948559 +EDGE3 2078 2079 -0.383013 4.05359 -0.169534 -0.0172697 -0.00368956 0.174349 +EDGE3 2081 2082 -0.340467 4.0127 0.0683315 -0.021181 0.0288935 0.0792961 +EDGE3 2080 2081 -0.348399 4.00885 -0.0061549 -0.0127559 0.00532245 0.109732 +EDGE3 2083 2084 -0.355871 3.94276 0.0545487 -0.0279213 -0.0106175 0.151973 +EDGE3 2082 2083 -0.239076 4.21758 0.159709 -0.000660526 -0.00489396 0.106588 +EDGE3 2085 2086 -0.638831 4.13665 -0.0376657 0.00645468 -0.0493665 0.138198 +EDGE3 2084 2085 -0.206529 4.07329 -0.0644068 0.0483776 -0.00317396 0.119356 +EDGE3 2087 2088 -0.437943 4.12418 -0.0314736 -0.00410521 -0.0174836 0.0950981 +EDGE3 2086 2087 -0.385467 3.87543 0.00442321 0.00391159 -0.0333253 0.101732 +EDGE3 2088 2089 -0.233343 4.02357 0.126569 -0.00398826 -0.0105054 0.142584 +EDGE3 2089 2090 -0.345758 4.19701 0.209383 0.00710551 0.00594399 0.11812 +EDGE3 2091 2092 -0.523829 3.95018 0.12284 0.00384545 -0.00988734 0.128046 +EDGE3 2090 2091 -0.238709 4.114 0.0694156 0.0195278 0.0052906 0.0873507 +EDGE3 2093 2094 -0.468779 3.99719 0.00149628 -0.00136685 0.0242758 0.122566 +EDGE3 2092 2093 -0.357733 3.98815 -0.112344 -0.0113886 0.0165248 0.0811303 +EDGE3 2095 2096 -0.343115 4.02607 -0.179906 -0.00137142 -0.0141484 0.118193 +EDGE3 2094 2095 -0.152154 4.09628 -0.0128303 0.0472699 0.00169536 0.13308 +EDGE3 2097 2098 -0.397498 3.94481 -0.0399098 0.00785127 0.00815518 0.146541 +EDGE3 2096 2097 -0.561775 3.68276 0.0304805 -0.0129884 0.000657146 0.150934 +EDGE3 2099 2100 -0.262284 3.97534 -0.0708596 0.0468841 0.000787167 0.12766 +EDGE3 2098 2099 -0.344704 4.03312 0.0364982 0.0503092 0.0274198 0.0790719 +EDGE3 2101 2102 -0.243919 3.90218 -0.043411 -0.0121436 0.0551011 0.135513 +EDGE3 2100 2101 -0.300191 3.90584 -0.079496 0.00411474 -0.018062 0.141545 +EDGE3 2103 2104 -0.370023 3.71395 -0.173548 -0.00319332 0.0068217 0.143651 +EDGE3 2102 2103 -0.373436 3.62371 -0.240326 -0.0147725 0.00585939 0.14323 +EDGE3 2105 2106 -0.271121 3.59149 -0.00521158 -0.0318148 -0.0229441 0.111739 +EDGE3 2104 2105 -0.366994 3.97445 0.0286571 0.0187668 0.0398842 0.140562 +EDGE3 2107 2108 -0.300902 3.88135 0.157735 0.00257844 0.000842808 0.108121 +EDGE3 2106 2107 -0.310479 3.79284 -0.00865958 0.00319283 0.0272631 0.139212 +EDGE3 2108 2109 -0.36613 3.78291 -0.0780083 0.0160674 -0.0271713 0.188626 +EDGE3 2109 2110 -0.359845 3.62636 -0.124719 0.0391131 0.0195548 0.116916 +EDGE3 2110 2111 -0.457321 3.7129 0.00377192 0.0484372 0.0320785 0.143974 +EDGE3 2111 2112 -0.393646 3.6869 -0.195922 0.00921651 0.0175116 0.125097 +EDGE3 2112 2113 -0.519908 3.78778 -0.0644208 -0.0108008 0.0174971 0.157071 +EDGE3 2113 2114 -0.229349 3.73056 -0.0148032 -0.00745241 0.0414395 0.126361 +EDGE3 2114 2115 -0.193192 3.55246 -0.228516 0.012054 0.00408945 0.121099 +EDGE3 2115 2116 -0.222599 3.50787 0.144924 0.0322544 -0.00458533 0.12141 +EDGE3 2116 2117 -0.268603 3.68938 -0.0532237 -0.0752953 0.00907558 0.117842 +EDGE3 2117 2118 -0.260218 3.55967 -0.0645148 0.0284328 0.00849421 0.147603 +EDGE3 2118 2119 -0.227869 3.52706 -0.0112385 -0.0482244 0.00744426 0.150821 +EDGE3 2119 2120 -0.329455 3.61025 0.0568174 -0.0545829 -0.0375774 0.115223 +EDGE3 2120 2121 -0.367203 3.61667 0.0261338 0.0395744 0.0308126 0.133276 +EDGE3 2121 2122 -0.376642 3.58524 -0.0650613 -0.0226514 -0.0151484 0.123784 +EDGE3 2122 2123 -0.291807 3.35753 -0.0136846 -0.00368396 -0.0278952 0.175945 +EDGE3 2123 2124 -0.338772 3.4126 -0.100525 -0.0431838 0.0383965 0.135469 +EDGE3 2124 2125 -0.313579 3.46764 -0.0177514 -0.0140072 -0.00857195 0.158676 +EDGE3 2125 2126 -0.304983 3.38346 0.0359959 -0.0128374 0.00432931 0.113893 +EDGE3 2126 2127 -0.456496 3.55347 0.0258878 -0.00955113 -0.0165964 0.0751755 +EDGE3 2127 2128 -0.376412 3.65576 0.0795448 0.0160295 -0.01699 0.114707 +EDGE3 2128 2129 -0.447092 3.40566 0.00259089 0.015369 -0.00933781 0.17731 +EDGE3 2129 2130 -0.384177 3.16738 -0.0412008 0.0029327 -0.0381975 0.0848206 +EDGE3 2130 2131 -0.249144 3.46968 0.0772509 0.0287055 -0.0014407 0.128105 +EDGE3 2131 2132 -0.569481 3.30907 0.0223868 -0.0334409 -0.026451 0.128195 +EDGE3 2132 2133 -0.381632 3.46961 0.0168547 0.0112736 -0.0192883 0.097197 +EDGE3 2133 2134 -0.277535 3.43106 0.00162986 0.0682083 0.00622863 0.139186 +EDGE3 2134 2135 -0.257373 3.32976 0.0537254 0.0102248 0.0520881 0.150005 +EDGE3 2135 2136 -0.500683 3.21517 -0.00655658 0.00440678 -0.00835893 0.13689 +EDGE3 2136 2137 -0.425913 3.38135 -0.0464894 -0.0295259 -0.0156306 0.126458 +EDGE3 2137 2138 -0.411947 3.37001 -0.0941055 0.0247919 0.0101788 0.160034 +EDGE3 2138 2139 -0.350875 3.37953 0.127347 -0.00227724 0.0161401 0.0781318 +EDGE3 2139 2140 -0.290386 3.22483 -0.0888212 0.0354362 -0.0294238 0.154179 +EDGE3 2140 2141 -0.414677 3.41706 -0.0785646 0.0585221 -0.0273342 0.169193 +EDGE3 2141 2142 -0.304253 3.22849 0.0222473 -0.04485 -0.0197185 0.149429 +EDGE3 2142 2143 -0.570469 3.03762 0.172966 0.00238423 0.0143802 0.105794 +EDGE3 2143 2144 -0.276433 3.14283 -0.229714 -0.0590761 -0.000852069 0.153949 +EDGE3 2144 2145 -0.476828 3.14647 -0.00497408 0.0218346 -0.0221408 0.123277 +EDGE3 2145 2146 -0.354536 3.28295 -0.0673383 0.0172952 -0.0322631 0.119778 +EDGE3 2146 2147 -0.262497 3.24927 0.0242772 -0.0376368 -0.00202607 0.147035 +EDGE3 2147 2148 -0.183434 3.11527 0.0607952 0.0102891 0.00339872 0.115713 +EDGE3 2148 2149 -0.26609 3.00762 -0.012202 -0.0206214 -0.0135885 0.149266 +EDGE3 2149 2150 -0.28481 3.03301 0.0261367 -0.0371017 0.00796192 0.142538 +EDGE3 2150 2151 -0.271156 3.07781 -0.0783475 0.0269962 0.0313542 0.116099 +EDGE3 2151 2152 -0.350715 3.05003 0.100727 0.0355376 0.000180312 0.100613 +EDGE3 2152 2153 -0.460707 3.03847 0.198754 0.0328567 0.0279823 0.158516 +EDGE3 2153 2154 -0.139386 3.26386 -0.115362 0.0040301 -0.0393049 0.130678 +EDGE3 2154 2155 -0.244288 3.05564 -0.19253 0.0486173 0.00494355 0.140303 +EDGE3 2155 2156 -0.539936 3.00394 0.0253834 0.00264492 0.00972574 0.139272 +EDGE3 2156 2157 -0.193718 3.13855 0.0848396 -0.0132581 -0.00568187 0.101724 +EDGE3 2157 2158 -0.129617 2.90492 -0.082859 0.0105433 0.00975997 0.130277 +EDGE3 2158 2159 -0.385451 3.04461 0.011358 -0.00816929 -0.00439847 0.155419 +EDGE3 2159 2160 -0.274864 3.12992 0.0111191 0.00963108 -0.0225251 0.132072 +EDGE3 2160 2161 -0.188753 3.16129 0.0158772 0.0253924 -0.0101975 0.146565 +EDGE3 2161 2162 -0.303669 2.81564 -0.233823 0.0109381 0.0270462 0.132246 +EDGE3 2162 2163 -0.272499 3.02014 -0.200364 -0.0481388 0.00446362 0.0901503 +EDGE3 2163 2164 -0.416703 2.94702 -0.00709744 0.0684473 0.00750391 0.121027 +EDGE3 2164 2165 -0.28055 2.9404 -0.0983855 -0.0341548 0.0332497 0.135951 +EDGE3 2165 2166 -0.308037 2.93372 0.114088 0.00879064 0.0100941 0.104938 +EDGE3 2166 2167 -0.295054 2.72435 -0.0958041 -0.0418857 0.0141957 0.14019 +EDGE3 2167 2168 -0.336536 2.99512 0.0453042 0.0092147 -0.0395417 0.114873 +EDGE3 2168 2169 -0.485427 2.59407 0.0435769 0.0112219 0.024779 0.15133 +EDGE3 2169 2170 -0.397112 3.11285 0.0233423 0.0109822 0.0219091 0.112808 +EDGE3 2170 2171 -0.237364 2.69977 0.0251846 -0.00945971 -0.0867999 0.145593 +EDGE3 2171 2172 -0.216685 2.71949 0.0793537 0.0334259 -0.0287089 0.143025 +EDGE3 2172 2173 -0.196393 2.7068 -0.0747247 0.0203775 -0.0114432 0.117915 +EDGE3 2173 2174 -0.244509 2.80858 0.0917827 0.0611263 -0.0282318 0.103042 +EDGE3 2174 2175 -0.303928 2.70238 0.0834894 0.0116897 -0.0384431 0.125828 +EDGE3 2175 2176 -0.178839 2.63782 -0.114192 -0.0403661 0.0167718 0.16091 +EDGE3 2176 2177 -0.365693 2.67761 -0.090914 0.00431867 0.0300641 0.144282 +EDGE3 2177 2178 -0.573187 2.69333 0.0321854 0.0440861 0.0122099 0.137537 +EDGE3 2178 2179 -0.241427 2.75633 0.123438 0.0390555 0.0164026 0.0916524 +EDGE3 2179 2180 -0.412806 2.71437 -0.126052 -0.0193805 -0.0327717 0.120305 +EDGE3 2180 2181 -0.223389 2.55472 -0.119283 0.0181588 0.00205435 0.149626 +EDGE3 2181 2182 -0.438496 2.61804 -0.258022 -0.00743053 0.00181643 0.134271 +EDGE3 2182 2183 -0.312247 2.8061 0.0262284 0.0179308 -0.0371144 0.123919 +EDGE3 2183 2184 -0.333049 2.57089 -0.0434236 0.000387814 0.0338181 0.105089 +EDGE3 2184 2185 -0.418959 2.62445 -0.0485909 0.0104749 -0.00935471 0.0976884 +EDGE3 2185 2186 -0.320784 2.6523 -0.0805229 -0.0029181 -0.00459747 0.13705 +EDGE3 2186 2187 -0.359886 2.77581 -0.00102536 0.0144222 0.0438116 0.174932 +EDGE3 2187 2188 -0.464076 2.37126 0.0230619 0.0403605 -0.00636144 0.13897 +EDGE3 2188 2189 -0.231647 2.50154 0.0574979 -0.0312312 0.0288644 0.137979 +EDGE3 2189 2190 -0.18352 2.52334 0.0630677 0.0412319 0.0183486 0.0894673 +EDGE3 2190 2191 -0.220055 2.49616 -0.0719331 0.022317 0.00697179 0.0780407 +EDGE3 2191 2192 -0.291871 2.36747 -0.0549767 0.0059337 -0.0266488 0.166061 +EDGE3 2192 2193 -0.363183 2.56969 -0.195767 -0.0486885 -0.0341254 0.0787843 +EDGE3 2193 2194 -0.396833 2.4404 -0.13062 0.00521292 0.0444312 0.151497 +EDGE3 2194 2195 -0.102905 2.33035 0.165493 0.00611316 0.0822779 0.147485 +EDGE3 2195 2196 -0.33889 2.47023 -0.0753643 -0.0130358 -0.00694314 0.107615 +EDGE3 2196 2197 -0.256704 2.42585 -0.0648995 -0.00503635 -0.0451276 0.102136 +EDGE3 2197 2198 -0.218847 2.29165 -0.00149348 0.0236019 0.00647133 0.133826 +EDGE3 2198 2199 -0.305947 2.28296 -0.0741077 0.00690545 -0.018478 0.123715 +EDGE3 0 50 6.11972 -0.00893354 -1.37462 -0.00140696 6.3417e-06 -0.00254705 +EDGE3 1 51 6.11514 -0.00290397 -1.38349 0.00562235 -0.00768984 0.00161913 +EDGE3 0 51 6.04391 3.14356 -1.41259 -0.00644228 0.00357308 0.131948 +EDGE3 1 50 5.83111 -3.10491 -1.36611 0.00458924 -0.000677471 -0.126733 +EDGE3 2 52 6.11412 0.00711414 -1.38086 -0.0015433 -0.00486572 -0.00645222 +EDGE3 1 52 6.03837 3.14063 -1.4057 0.00246388 0.000846598 0.131307 +EDGE3 2 51 5.80837 -3.12404 -1.34349 0.00367301 0.0142587 -0.115736 +EDGE3 3 53 6.12942 -0.0133073 -1.38707 0.000990927 0.00270694 -0.00150327 +EDGE3 2 53 6.05655 3.16355 -1.41058 -0.00499746 0.00859955 0.126062 +EDGE3 3 52 5.82319 -3.15449 -1.35521 0.0147945 -0.00398036 -0.120132 +EDGE3 4 54 6.1255 0.00296309 -1.38875 0.00235303 0.0027581 -0.00705106 +EDGE3 3 54 6.04319 3.1786 -1.41531 -0.00338597 0.000143261 0.126311 +EDGE3 4 53 5.80413 -3.14468 -1.36569 0.0105311 0.00455924 -0.125827 +EDGE3 5 55 6.12837 -0.0153614 -1.4065 0.00249087 -0.00194728 -0.0111866 +EDGE3 4 55 6.04289 3.18862 -1.43 0.00205797 -0.00614753 0.129514 +EDGE3 5 54 5.80003 -3.17592 -1.38066 -0.000825679 0.00145031 -0.137231 +EDGE3 6 56 6.12002 0.00234157 -1.43075 -0.00293303 -0.00241829 0.00800579 +EDGE3 5 56 6.03108 3.20151 -1.43091 0.00652512 0.000165788 0.125585 +EDGE3 6 55 5.79982 -3.19297 -1.37245 -0.00357574 -0.00680968 -0.113685 +EDGE3 7 57 6.12028 -0.00529645 -1.42844 0.00130073 -0.00793789 -0.00970794 +EDGE3 6 57 6.03646 3.2089 -1.4581 0.00614243 0.000840213 0.129426 +EDGE3 7 56 5.81089 -3.2101 -1.37476 -0.00116205 -0.00471664 -0.124446 +EDGE3 8 58 6.11394 -0.000244263 -1.41543 0.000683067 0.0069321 -0.00233103 +EDGE3 7 58 6.02528 3.24551 -1.46555 0.00215408 0.000398194 0.11986 +EDGE3 8 57 5.79834 -3.22258 -1.39436 0.00597684 -0.00685523 -0.128387 +EDGE3 9 59 6.11751 -0.00272915 -1.45837 -0.000896292 -0.00206561 0.00685052 +EDGE3 8 59 6.04778 3.25214 -1.46288 0.00084791 -0.00624071 0.115623 +EDGE3 9 58 5.799 -3.22677 -1.41648 0.00454012 0.00362566 -0.119379 +EDGE3 10 60 6.11508 0.00822253 -1.44906 0.00104493 -0.00745347 0.00189926 +EDGE3 9 60 6.02311 3.26098 -1.47035 -0.00682864 -0.00234109 0.118316 +EDGE3 10 59 5.7731 -3.24279 -1.42359 0.00105967 0.000812415 -0.119723 +EDGE3 11 61 6.11224 0.00529221 -1.45051 0.00509044 -0.000526403 0.00150985 +EDGE3 10 61 6.03088 3.27506 -1.4833 -0.00302734 0.00680906 0.125786 +EDGE3 11 60 5.78424 -3.27257 -1.44272 0.00453576 -0.00700791 -0.125021 +EDGE3 12 62 6.12548 0.00963191 -1.46432 -0.00217819 -0.00739997 0.00954359 +EDGE3 11 62 6.02053 3.30247 -1.49029 0.00278748 0.00433126 0.124884 +EDGE3 12 61 5.76208 -3.28478 -1.44483 0.00288805 0.000449133 -0.124563 +EDGE3 13 63 6.11576 0.00464429 -1.46125 -0.0100611 -7.30015e-06 -0.00366677 +EDGE3 12 63 6.03592 3.32433 -1.4844 -0.00393364 3.32169e-05 0.132115 +EDGE3 13 62 5.77712 -3.29756 -1.43531 -0.00652166 -0.000168746 -0.124441 +EDGE3 14 64 6.10133 0.00519366 -1.51067 -0.00302036 0.00457974 -0.000642689 +EDGE3 13 64 6.013 3.34303 -1.48952 -0.00553703 0.00135806 0.132571 +EDGE3 14 63 5.7757 -3.31015 -1.45119 -0.00138074 -0.0050302 -0.132279 +EDGE3 15 65 6.1119 -0.00885476 -1.50807 0.0010952 0.00259957 0.00385277 +EDGE3 14 65 6.00864 3.3564 -1.50614 -0.00112172 0.000604592 0.125188 +EDGE3 15 64 5.79546 -3.3311 -1.46713 -0.0108716 0.00233333 -0.126937 +EDGE3 16 66 6.09882 -0.00194252 -1.48662 -0.00167374 0.00665682 -0.00701816 +EDGE3 15 66 6.01572 3.34859 -1.52163 -0.00744685 0.00471465 0.126111 +EDGE3 16 65 5.77986 -3.35107 -1.47069 -0.000120601 0.00345986 -0.133812 +EDGE3 17 67 6.0892 0.00632952 -1.50137 -0.00515412 -0.00577457 0.00138417 +EDGE3 16 67 5.99839 3.38152 -1.52469 -0.00981933 0.00375253 0.121643 +EDGE3 17 66 5.77988 -3.37061 -1.46554 -0.00703118 0.00220301 -0.126292 +EDGE3 18 68 6.0957 0.00274021 -1.50315 0.0107457 0.00405349 0.00166667 +EDGE3 18 67 5.76555 -3.37926 -1.47646 -0.00831819 -0.00163993 -0.123521 +EDGE3 17 68 6.00516 3.38432 -1.52743 -0.00341189 -0.00293382 0.122562 +EDGE3 18 69 6.02081 3.41336 -1.55061 -0.0039215 0.000497732 0.120386 +EDGE3 19 69 6.09289 -0.0010636 -1.53527 -0.00434216 -0.0137288 0.00504408 +EDGE3 19 68 5.75096 -3.38374 -1.47753 -8.92084e-05 -0.0043936 -0.131904 +EDGE3 20 70 6.10776 -0.00165257 -1.52364 -0.00502246 -0.000853576 0.00452281 +EDGE3 20 69 5.75619 -3.41027 -1.47674 -0.000916691 0.00178291 -0.128619 +EDGE3 19 70 5.98449 3.41518 -1.53642 -0.00138635 -0.00702438 0.114834 +EDGE3 20 71 5.99928 3.42898 -1.53952 0.00496064 -0.00126123 0.117708 +EDGE3 21 71 6.1032 0.0020736 -1.5429 -0.00231419 -0.00209502 0.000297051 +EDGE3 21 70 5.7523 -3.42038 -1.49199 0.00313763 -0.00434981 -0.139778 +EDGE3 22 72 6.07901 0.00524933 -1.55217 -0.00042224 -0.00118569 -0.00240268 +EDGE3 22 71 5.76198 -3.44653 -1.49968 -0.00275238 -0.00466739 -0.1245 +EDGE3 21 72 5.99484 3.45407 -1.5764 0.00163465 -0.00991686 0.128759 +EDGE3 22 73 6.0027 3.45738 -1.56607 -0.0158309 -0.00836225 0.127586 +EDGE3 23 73 6.10082 0.0114996 -1.55869 -0.00459807 -0.00377348 -0.00275574 +EDGE3 23 72 5.74655 -3.437 -1.51677 -0.000104165 -0.00350296 -0.134412 +EDGE3 24 74 6.08705 -0.00174821 -1.5618 0.00225707 -0.0107219 -0.00484899 +EDGE3 24 73 5.74605 -3.46888 -1.53533 -0.00455136 -0.00164241 -0.113423 +EDGE3 23 74 6.00632 3.4872 -1.56678 0.00647538 -0.00825944 0.133528 +EDGE3 24 75 5.97269 3.49694 -1.5782 -0.00413921 0.00183854 0.128583 +EDGE3 25 75 6.08548 0.00644914 -1.56033 -0.00112687 0.00895353 0.00810095 +EDGE3 26 76 6.07292 0.0116776 -1.57593 0.00170253 0.00572192 -0.00189936 +EDGE3 25 74 5.74968 -3.4811 -1.5236 0.0031843 -0.00310187 -0.122483 +EDGE3 26 75 5.73831 -3.47876 -1.53688 0.00175372 0.00917918 -0.129456 +EDGE3 25 76 5.98043 3.49578 -1.6028 -0.00283601 -0.00217983 0.125177 +EDGE3 26 77 6.00535 3.51437 -1.60966 0.00406358 0.000828482 0.120604 +EDGE3 27 77 6.07569 -0.0167229 -1.58397 -0.00690304 -0.00266619 -0.00204782 +EDGE3 28 78 6.05775 -0.0026225 -1.58506 -0.00134303 0.00626699 0.00460407 +EDGE3 27 76 5.74584 -3.50261 -1.53829 0.00392433 0.0013632 -0.125453 +EDGE3 28 77 5.73282 -3.5292 -1.55189 0.006444 -0.000873506 -0.128736 +EDGE3 27 78 5.97786 3.55065 -1.64091 0.000196978 -0.00241483 0.114408 +EDGE3 29 79 6.07839 0.00871151 -1.60479 0.000653261 0.00125151 -0.00440816 +EDGE3 28 79 5.95552 3.56276 -1.60466 0.000431372 -0.00350532 0.128129 +EDGE3 30 80 6.07887 -0.000467234 -1.59729 -0.0050971 0.00315035 -0.00538498 +EDGE3 29 78 5.7384 -3.53912 -1.55937 -0.0146235 0.0096842 -0.123732 +EDGE3 30 79 5.74311 -3.54913 -1.58299 0.00400892 0.00381975 -0.124435 +EDGE3 29 80 5.97867 3.55793 -1.63818 3.63498e-05 0.00167426 0.122272 +EDGE3 30 81 5.97535 3.58252 -1.63017 -0.0104082 -0.00788805 0.133384 +EDGE3 31 81 6.07709 0.00789514 -1.63126 0.00235593 -0.00263501 0.00452326 +EDGE3 31 80 5.74026 -3.56241 -1.5681 -0.00137377 0.00602363 -0.122371 +EDGE3 32 82 6.09127 -0.00170803 -1.62439 0.000905333 0.00893894 -0.00543269 +EDGE3 32 81 5.70358 -3.58975 -1.58553 0.00460823 0.00443611 -0.120746 +EDGE3 31 82 5.97333 3.60952 -1.66157 -0.00745494 0.00936585 0.118701 +EDGE3 32 83 5.95712 3.61499 -1.65999 0.0100373 0.00615694 0.127332 +EDGE3 33 83 6.07521 0.0215373 -1.61475 -0.00378559 -0.0106738 -0.000936307 +EDGE3 34 84 6.06661 0.0131072 -1.6243 0.00127815 -0.00414332 -0.00297664 +EDGE3 33 82 5.72509 -3.61366 -1.60653 0.00670891 0.0023183 -0.127472 +EDGE3 34 83 5.70783 -3.62572 -1.60243 -0.0117971 -0.000496231 -0.122681 +EDGE3 33 84 5.95487 3.6237 -1.64215 -0.00381053 0.00197684 0.130719 +EDGE3 34 85 5.96025 3.63742 -1.6773 0.00298356 -0.00661316 0.123014 +EDGE3 35 85 6.06855 -0.00601976 -1.64585 -0.00306934 -0.00628035 0.00914347 +EDGE3 36 86 6.0482 -0.00545503 -1.63736 0.0058088 0.00763211 -0.00139153 +EDGE3 35 84 5.71811 -3.61977 -1.59417 0.00619054 0.0013204 -0.131927 +EDGE3 36 85 5.69827 -3.64089 -1.61004 0.00619133 -0.00274829 -0.120178 +EDGE3 35 86 5.95059 3.68645 -1.67028 0.00463549 -0.00507429 0.124095 +EDGE3 36 87 5.91882 3.68691 -1.66845 -0.00539114 0.00509546 0.121941 +EDGE3 37 87 6.04133 -0.00512753 -1.66253 0.0110282 0.00265496 0.00291036 +EDGE3 37 86 5.71234 -3.65366 -1.61589 0.00118313 0.000680967 -0.119826 +EDGE3 38 88 6.05637 0.00572577 -1.66459 -0.00109847 0.00202454 -0.00201039 +EDGE3 38 87 5.71034 -3.67735 -1.63441 0.00167769 -0.00181151 -0.123806 +EDGE3 37 88 5.96495 3.68893 -1.68873 -0.00201893 0.000114073 0.119409 +EDGE3 38 89 5.93434 3.69993 -1.68917 -0.00450868 0.00357424 0.124044 +EDGE3 39 89 6.05151 0.00204118 -1.65308 -0.00337722 -0.00555212 0.00190195 +EDGE3 40 90 6.05717 0.00215565 -1.67535 -0.00314402 0.00164513 -0.00262336 +EDGE3 39 88 5.70599 -3.69934 -1.62652 0.0115456 0.00480078 -0.126253 +EDGE3 40 89 5.70788 -3.71013 -1.6514 0.00160722 0.0126867 -0.116163 +EDGE3 39 90 5.96413 3.73711 -1.71614 0.00282817 0.00199093 0.116416 +EDGE3 41 91 6.02996 0.00340548 -1.6772 -0.00172707 -0.00578159 4.41152e-05 +EDGE3 40 91 5.94827 3.74233 -1.72612 0.00544204 -0.000112154 0.131835 +EDGE3 42 92 6.04331 -5.52922e-05 -1.67095 -0.00376112 0.00836861 -0.00166795 +EDGE3 41 90 5.69804 -3.71125 -1.64371 -0.00187847 -0.00113179 -0.124437 +EDGE3 42 91 5.70507 -3.74148 -1.652 -0.00256422 0.00467398 -0.128983 +EDGE3 41 92 5.93401 3.74396 -1.72775 -0.00230964 -0.0118949 0.121803 +EDGE3 43 93 6.04352 0.0112597 -1.69363 -0.00176643 -0.00236959 -0.00114396 +EDGE3 42 93 5.93332 3.75536 -1.72847 -0.00972283 0.0128125 0.131137 +EDGE3 43 92 5.70351 -3.74262 -1.65159 -0.00610045 0.00014783 -0.127868 +EDGE3 44 94 6.0404 -0.00701323 -1.71356 -0.012758 0.00297533 0.00231851 +EDGE3 44 93 5.66988 -3.75656 -1.66603 -0.00108493 0.00543821 -0.123818 +EDGE3 43 94 5.9224 3.8029 -1.75138 0.00756069 -0.00963278 0.126029 +EDGE3 45 95 6.0476 -0.00331057 -1.70741 -0.000275016 -0.000828961 -0.00885021 +EDGE3 44 95 5.92909 3.80093 -1.74291 0.00392362 -0.00517788 0.123572 +EDGE3 45 94 5.69054 -3.78947 -1.64988 -0.0043428 0.00497947 -0.121811 +EDGE3 46 96 6.04318 -0.0154277 -1.71302 0.00101432 0.000319837 0.00350709 +EDGE3 46 95 5.69722 -3.799 -1.68612 0.000737577 -0.0052598 -0.133251 +EDGE3 45 96 5.91098 3.8227 -1.74532 -0.00510277 0.00123765 0.128198 +EDGE3 47 97 6.02878 -0.000466955 -1.73518 0.00200047 -0.00280864 0.00639932 +EDGE3 46 97 5.94027 3.82516 -1.75217 0.00133727 -0.00438804 0.123545 +EDGE3 47 96 5.68469 -3.80975 -1.69467 0.00501961 0.00298858 -0.121042 +EDGE3 48 98 6.02799 -0.0078803 -1.73595 -0.00298315 -0.00249077 -0.00261699 +EDGE3 48 97 5.67953 -3.82498 -1.69742 0.00200933 0.00482214 -0.121903 +EDGE3 47 98 5.92121 3.83587 -1.78062 -0.00859352 0.0102645 0.12717 +EDGE3 48 99 5.89924 3.83969 -1.76523 0.00296935 -0.00170359 0.126294 +EDGE3 49 99 6.03454 0.0159482 -1.75145 -0.00398306 0.00322142 -0.00156115 +EDGE3 49 98 5.66837 -3.83309 -1.69796 -0.0101816 0.00165774 -0.134616 +EDGE3 50 100 6.0531 0.00240527 -1.75145 0.00411842 -0.00588856 0.00643063 +EDGE3 50 99 5.68042 -3.87551 -1.72859 0.00930807 -0.00118271 -0.125911 +EDGE3 49 100 5.91226 3.88987 -1.77621 -0.00225962 -0.00787795 0.122022 +EDGE3 51 101 6.03686 0.000657682 -1.76089 0.00628174 -0.00268936 -0.000874877 +EDGE3 50 101 5.91108 3.90306 -1.79918 0.00509332 0.00471123 0.123859 +EDGE3 51 100 5.66957 -3.87177 -1.72535 0.00669151 0.00645065 -0.121051 +EDGE3 51 102 5.8956 3.89896 -1.80576 -0.000906502 0.00182485 0.127674 +EDGE3 52 102 6.03728 0.021938 -1.77295 -0.000403002 -0.00384297 0.0103737 +EDGE3 53 103 6.03234 0.00942228 -1.7609 0.0014608 0.00436922 -0.00697081 +EDGE3 52 101 5.67377 -3.89812 -1.71417 -0.00393782 0.000205524 -0.119897 +EDGE3 53 102 5.6672 -3.89522 -1.7396 -0.00551343 0.00523723 -0.124743 +EDGE3 52 103 5.89539 3.93757 -1.80931 -0.00399877 -0.0026882 0.124382 +EDGE3 53 104 5.90106 3.92763 -1.8006 -0.00652602 0.00963387 0.125856 +EDGE3 54 104 6.00989 0.00351003 -1.77361 0.0105765 0.00178354 0.00350889 +EDGE3 54 103 5.65164 -3.91323 -1.75306 -0.00385172 -0.000520094 -0.129294 +EDGE3 55 105 6.03449 -0.0101708 -1.78792 -0.00157436 0.000837582 -0.00612044 +EDGE3 55 104 5.64169 -3.92853 -1.74457 0.000971946 -0.00204357 -0.12908 +EDGE3 54 105 5.88807 3.94929 -1.82509 -0.00351371 0.0021823 0.134014 +EDGE3 55 106 5.896 3.94648 -1.83918 0.00229979 0.00462339 0.124973 +EDGE3 56 106 6.01795 0.000289357 -1.7949 -0.00407186 -0.00126609 0.000479507 +EDGE3 56 105 5.64194 -3.95722 -1.76479 0.00367483 -0.000108103 -0.129101 +EDGE3 57 107 6.01889 -0.00401374 -1.79805 0.00417964 0.00311521 -0.00731797 +EDGE3 56 107 5.89403 3.98321 -1.82501 -0.000395498 7.39681e-05 0.128587 +EDGE3 57 106 5.64834 -3.97073 -1.7447 -0.00821173 0.00201262 -0.128365 +EDGE3 58 108 6.00971 0.00320372 -1.81931 -0.00322353 -0.00254353 -0.00357634 +EDGE3 57 108 5.87502 3.9924 -1.84262 -0.00681329 0.00478126 0.131855 +EDGE3 58 107 5.63614 -3.98315 -1.7678 -0.00297391 0.00084563 -0.122423 +EDGE3 59 109 6.01502 0.00367891 -1.83032 0.00405322 0.00170815 0.0102004 +EDGE3 58 109 5.88189 4.00595 -1.8665 -0.00139562 0.000522079 0.1347 +EDGE3 59 108 5.63889 -3.97906 -1.7831 0.00571502 0.00510993 -0.128205 +EDGE3 60 110 6.01105 0.00486262 -1.83422 -0.00457399 -0.00937262 0.00465961 +EDGE3 59 110 5.87321 4.04018 -1.85452 -0.00305856 -0.00302085 0.116906 +EDGE3 60 109 5.65083 -3.99674 -1.78317 0.00636851 0.00326326 -0.130214 +EDGE3 61 111 5.99294 -0.00403463 -1.84267 -2.53093e-05 -0.00461734 0.0045153 +EDGE3 60 111 5.86589 4.03051 -1.86926 0.00811962 -0.00179903 0.131346 +EDGE3 61 110 5.63079 -4.03171 -1.78604 -0.00751893 0.00848692 -0.132133 +EDGE3 62 112 6.00123 -0.0225977 -1.86017 0.00639095 0.00361916 0.00858639 +EDGE3 61 112 5.86269 4.05155 -1.86056 -0.00168688 -0.00519357 0.132769 +EDGE3 62 111 5.63413 -4.04472 -1.81469 -0.00271435 0.00562838 -0.11943 +EDGE3 63 113 6.01285 0.0024979 -1.84839 0.00125242 -0.00745156 0.00238935 +EDGE3 62 113 5.86038 4.06022 -1.89464 0.00866457 0.00730321 0.11955 +EDGE3 63 112 5.62836 -4.04302 -1.80749 -0.00462706 0.00052154 -0.135054 +EDGE3 64 114 6.00514 0.0107073 -1.8577 -0.00246795 0.00661229 -0.00271618 +EDGE3 63 114 5.85389 4.08625 -1.89571 -0.0016836 0.000585519 0.123909 +EDGE3 64 113 5.6221 -4.05993 -1.80437 -0.00357727 0.00397533 -0.130237 +EDGE3 65 115 5.97423 -0.00124733 -1.86892 0.0107997 6.49482e-06 0.00278011 +EDGE3 64 115 5.8562 4.10172 -1.89133 -0.00358338 0.00653456 0.120558 +EDGE3 65 114 5.61346 -4.09308 -1.84484 -0.00176369 -0.00548107 -0.128441 +EDGE3 66 116 6.00761 0.00534811 -1.88 -0.00550347 0.00739692 0.00235886 +EDGE3 65 116 5.85984 4.10187 -1.915 -0.00295189 0.00231472 0.129399 +EDGE3 66 115 5.63176 -4.10504 -1.82524 0.00137605 0.000780177 -0.127757 +EDGE3 67 117 5.98894 0.00877832 -1.88028 0.0030903 0.00068311 -0.0034402 +EDGE3 66 117 5.8582 4.12491 -1.89571 -0.000927213 -0.00216092 0.122863 +EDGE3 67 116 5.60413 -4.11751 -1.83832 -0.00945141 -0.00607642 -0.133117 +EDGE3 68 118 5.98853 -0.0199316 -1.888 -1.72056e-05 0.00215641 -0.000416189 +EDGE3 67 118 5.85264 4.13973 -1.9045 0.00249698 0.00152702 0.118707 +EDGE3 68 117 5.60264 -4.1509 -1.84876 0.00502446 0.000825705 -0.116886 +EDGE3 69 119 5.98526 -0.00951125 -1.88391 -0.00183865 -0.00276394 -0.00258148 +EDGE3 68 119 5.86141 4.15074 -1.91434 0.00725971 0.00326193 0.122789 +EDGE3 69 118 5.6027 -4.13985 -1.86089 -0.00364568 0.00598778 -0.121289 +EDGE3 70 120 5.99651 -0.00380666 -1.89442 0.00373236 0.00828163 0.0101294 +EDGE3 69 120 5.84588 4.1912 -1.93315 0.000848833 -0.0051159 0.128787 +EDGE3 70 119 5.6231 -4.16327 -1.86491 -0.00587796 0.00178752 -0.128629 +EDGE3 71 121 5.98972 0.00592975 -1.90604 0.00502805 0.00442367 0.00408159 +EDGE3 70 121 5.84565 4.17928 -1.92629 -3.7778e-05 0.00844592 0.126213 +EDGE3 71 120 5.61305 -4.16728 -1.85273 0.000778363 0.000255474 -0.12405 +EDGE3 72 122 5.97803 -0.0122998 -1.9405 -0.00469539 -0.00196644 -0.000187522 +EDGE3 71 122 5.82896 4.21127 -1.96047 0.00158939 -0.000391047 0.129698 +EDGE3 72 121 5.61647 -4.19136 -1.87703 0.00110015 -0.00156968 -0.133313 +EDGE3 73 123 5.97932 -0.000350682 -1.92511 -0.00190039 0.00754586 -0.000459796 +EDGE3 72 123 5.82336 4.21635 -1.96844 -0.00818846 -0.00331346 0.130343 +EDGE3 73 122 5.59325 -4.19327 -1.88537 0.0067114 0.0010906 -0.129288 +EDGE3 74 124 5.97536 0.005986 -1.90834 0.0071056 -0.00584422 -0.00740203 +EDGE3 73 124 5.83579 4.23927 -1.98399 -0.000376386 0.00294787 0.119293 +EDGE3 74 123 5.59857 -4.21007 -1.89681 0.000835168 0.00501631 -0.124868 +EDGE3 75 125 5.97123 0.000836197 -1.92828 0.0033444 -0.000389582 0.0035775 +EDGE3 74 125 5.82021 4.22932 -1.95624 -0.000652997 0.00174419 0.120155 +EDGE3 75 124 5.58109 -4.23365 -1.89523 0.00211956 -0.0025085 -0.128198 +EDGE3 76 126 5.97962 -0.00338912 -1.93769 0.00724903 0.00673398 -0.000199736 +EDGE3 75 126 5.81015 4.2486 -1.97798 0.00126694 -0.00140472 0.126549 +EDGE3 76 125 5.56677 -4.25114 -1.91582 0.00538321 -0.00431924 -0.129771 +EDGE3 77 127 5.96511 0.00893781 -1.95147 -0.000695422 0.00851389 -0.00629203 +EDGE3 76 127 5.82324 4.25904 -1.98487 -0.00768402 0.00276818 0.132595 +EDGE3 77 126 5.58485 -4.25162 -1.92233 -0.0054113 -0.000870646 -0.126026 +EDGE3 78 128 5.96684 0.0106055 -1.96988 -0.00468598 -0.00565406 0.00478326 +EDGE3 77 128 5.80221 4.29024 -2.01328 0.00199218 -0.00993031 0.128122 +EDGE3 78 127 5.58807 -4.2686 -1.92474 0.00301168 0.00879572 -0.122302 +EDGE3 79 129 5.97656 0.00365134 -1.96406 -0.00398241 0.000860163 0.00169638 +EDGE3 78 129 5.81543 4.32468 -2.00892 -0.00374706 -0.00115868 0.120855 +EDGE3 79 128 5.57724 -4.27281 -1.90963 0.00618196 -0.0020938 -0.131176 +EDGE3 80 130 5.96562 -0.00161367 -1.97003 0.00411857 -0.00158802 -0.00244967 +EDGE3 79 130 5.82018 4.31862 -2.01151 -0.00211037 0.0165855 0.129756 +EDGE3 80 129 5.56852 -4.3028 -1.91962 0.0025639 -0.00394968 -0.120306 +EDGE3 81 131 5.94521 0.0162818 -1.9948 -0.00172237 0.000865583 -0.00260826 +EDGE3 80 131 5.82783 4.35356 -2.03651 0.00598564 -0.000982933 0.124428 +EDGE3 81 130 5.55323 -4.31746 -1.92856 0.00540562 0.00496053 -0.128523 +EDGE3 82 132 5.96408 0.0020805 -1.96162 -0.000683424 -0.000772931 0.00759713 +EDGE3 81 132 5.8125 4.34462 -2.04241 0.00161407 -7.70415e-05 0.124894 +EDGE3 82 131 5.56577 -4.33336 -1.94502 0.000679807 -0.00364073 -0.131766 +EDGE3 83 133 5.94316 0.00238086 -2.03116 0.00152152 0.00274034 0.0142897 +EDGE3 82 133 5.80439 4.34888 -2.02987 -0.00527469 -0.00410501 0.12436 +EDGE3 83 132 5.57623 -4.35223 -1.96252 0.00181198 -0.00303318 -0.132748 +EDGE3 84 134 5.95646 -0.0180557 -2.03408 -0.0103255 -0.00724995 0.00136713 +EDGE3 83 134 5.78748 4.37572 -2.0411 0.00221214 -0.00761497 0.123993 +EDGE3 84 133 5.55653 -4.37245 -1.96775 0.00709833 -0.00281156 -0.125832 +EDGE3 85 135 5.94208 0.00493401 -2.02688 0.00472784 -3.47198e-05 0.00591051 +EDGE3 84 135 5.79381 4.39278 -2.04457 -0.0041578 -0.00321466 0.122687 +EDGE3 85 134 5.56439 -4.38217 -1.97612 0.00526743 0.0115213 -0.112686 +EDGE3 86 136 5.94761 0.00671231 -2.02566 -0.00306292 -0.00317852 0.0115797 +EDGE3 85 136 5.79455 4.42109 -2.06022 0.00803026 0.00599991 0.121686 +EDGE3 86 135 5.55584 -4.39217 -1.97548 0.0073747 0.000987974 -0.123783 +EDGE3 87 137 5.94259 -0.00115577 -2.031 0.000740562 -0.00239206 -0.00923927 +EDGE3 86 137 5.77271 4.43999 -2.05869 0.00256194 0.00475416 0.126048 +EDGE3 87 136 5.55483 -4.42709 -1.98169 0.00557298 0.000198146 -0.134599 +EDGE3 88 138 5.94258 -0.00361728 -2.04355 0.00481512 -0.011422 -0.00249253 +EDGE3 87 138 5.78317 4.43385 -2.1069 0.00370164 0.00368922 0.119196 +EDGE3 88 137 5.53985 -4.42804 -1.98674 0.00509582 0.00338233 -0.130823 +EDGE3 89 139 5.94516 -0.00249866 -2.03337 -0.00859126 0.00295914 -0.00537613 +EDGE3 88 139 5.77471 4.44999 -2.0936 -0.00717492 -0.00362283 0.124473 +EDGE3 89 138 5.54099 -4.44564 -2.00634 -0.0110852 -0.000549116 -0.127031 +EDGE3 90 140 5.94748 -0.00306102 -2.04996 -0.00625194 -0.00152921 -0.00129463 +EDGE3 89 140 5.77254 4.44635 -2.08843 0.00515903 -0.0054336 0.128899 +EDGE3 90 139 5.54158 -4.44279 -2.01508 -0.000136648 -0.00381583 -0.124038 +EDGE3 91 141 5.94033 -0.00592582 -2.04659 -0.00248979 -0.00513761 -0.00388407 +EDGE3 90 141 5.76119 4.48277 -2.10685 -0.00347186 -0.0045345 0.124881 +EDGE3 91 140 5.54484 -4.46782 -2.00898 0.00308155 0.00244027 -0.133813 +EDGE3 92 142 5.93628 -0.00700654 -2.07294 0.00242552 -0.00272029 -0.00377451 +EDGE3 91 142 5.75676 4.50852 -2.10521 0.00750575 0.00459178 0.121185 +EDGE3 92 141 5.53831 -4.48086 -2.03158 0.011379 0.00496877 -0.122346 +EDGE3 93 143 5.93916 -0.0118729 -2.08482 0.00111161 -0.00246535 -0.00710477 +EDGE3 92 143 5.76493 4.50571 -2.09541 -0.00329549 0.0046654 0.126824 +EDGE3 93 142 5.54164 -4.49599 -2.03001 -0.000962885 0.00280491 -0.118919 +EDGE3 94 144 5.9335 -0.0057197 -2.09441 -0.0018911 -0.000335212 -0.00478258 +EDGE3 93 144 5.77849 4.53759 -2.10989 0.00329856 0.00355965 0.129626 +EDGE3 94 143 5.51396 -4.51852 -2.03305 -0.00422389 -0.00690553 -0.123483 +EDGE3 95 145 5.91591 0.000661672 -2.10186 -0.00145643 0.0014295 0.00148329 +EDGE3 94 145 5.75588 4.54557 -2.11957 -0.000482724 -0.00460314 0.120762 +EDGE3 95 144 5.50652 -4.53556 -2.05973 0.00106481 0.00596608 -0.127319 +EDGE3 96 146 5.91818 0.00555718 -2.09958 0.00445131 -0.00633504 0.0034371 +EDGE3 95 146 5.76897 4.54789 -2.15406 0.0125085 -0.00391636 0.126051 +EDGE3 96 145 5.52807 -4.54252 -2.05661 -0.00142262 -0.00201221 -0.123565 +EDGE3 97 147 5.92883 -0.00816408 -2.10848 -0.00851119 0.00167811 0.00396104 +EDGE3 96 147 5.7446 4.55625 -2.14862 -0.00362468 0.000322689 0.122169 +EDGE3 97 146 5.50413 -4.55442 -2.04778 -0.00168099 -0.00224073 -0.122386 +EDGE3 98 148 5.91495 -0.02329 -2.11426 -0.00255287 -0.00118894 -0.00125806 +EDGE3 97 148 5.75839 4.59625 -2.15156 0.00515329 0.0109351 0.127274 +EDGE3 98 147 5.50959 -4.55731 -2.05593 -0.00649675 0.00817046 -0.122436 +EDGE3 99 149 5.92614 0.00563662 -2.11202 -0.0039517 -0.00045968 -0.0034078 +EDGE3 98 149 5.75515 4.59924 -2.1584 -0.00189203 0.00378308 0.113912 +EDGE3 99 148 5.50266 -4.58317 -2.06714 -0.00452115 -0.00812471 -0.124576 +EDGE3 100 150 5.89927 -0.00171002 -2.12712 0.00975283 -0.00121676 0.00218433 +EDGE3 99 150 5.74189 4.59605 -2.17907 -0.0111121 -0.0093574 0.127396 +EDGE3 100 149 5.53721 -4.59747 -2.09629 -0.000313599 -0.00408999 -0.116414 +EDGE3 101 151 5.90943 0.00669807 -2.13923 -0.0114859 -0.00141246 0.00114711 +EDGE3 100 151 5.74882 4.61929 -2.16734 -0.00121867 0.000422508 0.125296 +EDGE3 101 150 5.51791 -4.61208 -2.09307 0.00064946 0.00147765 -0.119846 +EDGE3 102 152 5.91426 -0.0046948 -2.16166 0.00899636 0.00926201 -0.000597472 +EDGE3 101 152 5.73251 4.62673 -2.15896 -6.3422e-05 0.00758668 0.123069 +EDGE3 102 151 5.5065 -4.62967 -2.09849 -0.00404858 -0.00638891 -0.124717 +EDGE3 103 153 5.89028 -0.0105186 -2.15423 0.00653543 0.00131055 -0.007956 +EDGE3 102 153 5.73193 4.66068 -2.18882 -0.00259482 -0.00358205 0.126595 +EDGE3 103 152 5.49435 -4.63766 -2.10545 -0.00706556 -0.00584102 -0.122815 +EDGE3 104 154 5.91477 -0.00162084 -2.16084 0.0084456 0.00810927 -0.00261921 +EDGE3 103 154 5.74257 4.6813 -2.20924 -0.00360991 9.95637e-05 0.12444 +EDGE3 104 153 5.47923 -4.65323 -2.13027 0.000952286 -0.00104826 -0.124772 +EDGE3 105 155 5.90082 -0.0256945 -2.17346 0.0044721 -0.0015286 0.00186278 +EDGE3 104 155 5.70767 4.69517 -2.21296 -0.00367287 -0.00751175 0.112486 +EDGE3 105 154 5.48129 -4.67686 -2.1206 -0.0091494 0.00362415 -0.130924 +EDGE3 106 156 5.87398 0.00822346 -2.18284 -0.00191114 0.0121077 -0.000770441 +EDGE3 106 155 5.4691 -4.68429 -2.10923 -0.00144972 0.0108972 -0.12369 +EDGE3 105 156 5.70191 4.70367 -2.21478 0.00103006 0.00844556 0.127081 +EDGE3 107 157 5.89072 0.0034803 -2.18206 0.00473961 -0.00198469 0.000331075 +EDGE3 107 156 5.48947 -4.69443 -2.14727 -0.000488885 -0.000787864 -0.121187 +EDGE3 106 157 5.71296 4.70389 -2.22313 -0.00590836 -0.0048013 0.130996 +EDGE3 107 158 5.71809 4.7096 -2.22289 -0.00234133 0.00693978 0.121249 +EDGE3 108 158 5.88531 0.000829966 -2.18625 0.00392153 -0.00256932 0.00319547 +EDGE3 109 159 5.90608 0.0096382 -2.18957 -0.00562035 0.00756161 -3.9901e-06 +EDGE3 108 157 5.49402 -4.72491 -2.14124 -0.0019229 0.0050416 -0.127212 +EDGE3 109 158 5.48339 -4.72683 -2.14706 0.0066325 0.00213795 -0.12895 +EDGE3 108 159 5.69969 4.76387 -2.24174 0.000527659 0.0028797 0.124346 +EDGE3 110 160 5.89676 0.0119852 -2.19602 -0.000331319 -0.00125258 -0.00494893 +EDGE3 109 160 5.70302 4.77212 -2.23386 0.000903606 0.0114715 0.125686 +EDGE3 110 159 5.47188 -4.75354 -2.15492 -0.0071824 -0.00102591 -0.123905 +EDGE3 110 161 5.6997 4.76112 -2.24607 -0.00261295 0.00721901 0.126415 +EDGE3 111 161 5.87787 -0.0244173 -2.20934 0.00368255 0.000942475 -0.00406739 +EDGE3 112 162 5.86889 -0.00562809 -2.23451 0.00541625 -0.00340068 -0.00696874 +EDGE3 111 160 5.46021 -4.74912 -2.16461 0.000464701 -0.00172643 -0.124538 +EDGE3 111 162 5.69558 4.79227 -2.24369 -0.00110732 -0.00286821 0.12321 +EDGE3 112 161 5.4535 -4.76453 -2.17599 0.00162129 0.0101455 -0.124948 +EDGE3 112 163 5.69631 4.80607 -2.25245 0.00800149 0.00366524 0.126133 +EDGE3 113 163 5.88131 0.00311327 -2.211 -0.00451385 0.00750783 0.00244361 +EDGE3 114 164 5.87413 -0.000175372 -2.2373 -0.00245302 -0.00390279 0.00417027 +EDGE3 113 162 5.4606 -4.78171 -2.18494 -0.00233199 -0.00620389 -0.126769 +EDGE3 114 163 5.4578 -4.80116 -2.17808 -0.00370648 0.00104254 -0.120747 +EDGE3 113 164 5.67238 4.80009 -2.27183 0.0037754 -0.00236843 0.131 +EDGE3 114 165 5.68948 4.83358 -2.28606 -0.00706079 0.00382505 0.126379 +EDGE3 115 165 5.87474 0.0111029 -2.24937 -0.00384167 0.00163294 -0.00326941 +EDGE3 116 166 5.87354 -0.00199616 -2.24632 -0.00320704 -0.00584065 0.00383598 +EDGE3 115 164 5.46442 -4.81239 -2.18844 -0.00589885 0.00580503 -0.112992 +EDGE3 115 166 5.67641 4.8502 -2.28855 -0.00134322 3.48353e-05 0.127661 +EDGE3 116 165 5.4475 -4.81495 -2.19482 0.000139381 0.00256851 -0.129053 +EDGE3 116 167 5.66491 4.86528 -2.29585 -0.00477419 -0.00059989 0.131747 +EDGE3 117 167 5.87944 -0.0124728 -2.24469 -0.0107505 0.00696478 0.00193708 +EDGE3 118 168 5.85323 0.00571888 -2.26368 0.00322066 0.00520114 -0.00501883 +EDGE3 117 166 5.44706 -4.83286 -2.19908 0.000646507 0.00265544 -0.127321 +EDGE3 118 167 5.45001 -4.85537 -2.23138 -0.000403095 -0.00734491 -0.119992 +EDGE3 117 168 5.64922 4.88115 -2.29113 -0.00647886 -0.00235151 0.108707 +EDGE3 118 169 5.67006 4.88958 -2.29077 -0.00533963 -0.00247105 0.117073 +EDGE3 119 169 5.86033 0.0139012 -2.28436 -0.00731334 -0.00208742 -0.00715914 +EDGE3 120 170 5.85089 -0.00562153 -2.2838 0.00642547 0.00940477 -0.00208428 +EDGE3 119 168 5.42989 -4.86642 -2.22973 -0.00835869 -0.0023744 -0.119837 +EDGE3 120 169 5.44382 -4.88834 -2.21988 0.00391662 -0.00224901 -0.115502 +EDGE3 119 170 5.67647 4.89386 -2.30626 -0.00382326 0.00174977 0.132028 +EDGE3 120 171 5.65423 4.91245 -2.31495 -0.00161161 0.00355253 0.130867 +EDGE3 121 171 5.8582 -0.0061348 -2.29434 -0.000618087 0.00568092 0.000994068 +EDGE3 122 172 5.8349 0.0074152 -2.29339 -0.000347891 -0.000551568 -0.00377615 +EDGE3 121 170 5.42134 -4.91352 -2.22649 -0.00193692 -0.00217144 -0.124404 +EDGE3 122 171 5.42522 -4.92462 -2.21826 -0.00308573 -0.00296274 -0.12297 +EDGE3 121 172 5.64846 4.93566 -2.33134 0.014239 -0.00915116 0.12262 +EDGE3 122 173 5.66465 4.94408 -2.34903 -0.00190267 -0.00257364 0.123996 +EDGE3 123 173 5.8491 0.0105335 -2.29719 -0.00523605 0.00332237 0.00470214 +EDGE3 124 174 5.85034 0.0104126 -2.29107 0.0103412 -0.0032568 -0.00540688 +EDGE3 123 172 5.41278 -4.92991 -2.23374 -0.00593764 0.00273019 -0.127082 +EDGE3 124 173 5.40336 -4.95046 -2.27406 -0.00203444 0.00612564 -0.119921 +EDGE3 123 174 5.63452 4.9648 -2.35178 0.00148572 -0.000824591 0.128495 +EDGE3 124 175 5.63355 4.97256 -2.34242 0.00432748 0.00132032 0.128943 +EDGE3 125 175 5.86013 0.013637 -2.33266 -0.00317936 0.00139432 -0.0052309 +EDGE3 126 176 5.83958 -0.00734298 -2.31412 -0.00441762 0.000826256 0.00078006 +EDGE3 125 174 5.41067 -4.96335 -2.26176 0.00742763 -0.00104166 -0.131905 +EDGE3 125 176 5.63856 4.99214 -2.38472 0.0130859 -0.00667206 0.118375 +EDGE3 126 175 5.4053 -4.95672 -2.27088 -0.000778198 0.0054299 -0.124555 +EDGE3 127 177 5.83927 -0.00122769 -2.32478 0.000477313 -0.00325058 0.00831139 +EDGE3 126 177 5.64143 5.01691 -2.35627 0.00473058 0.00394112 0.131258 +EDGE3 127 176 5.42368 -4.9976 -2.26462 -0.00442978 -0.00228202 -0.122 +EDGE3 127 178 5.64677 5.03737 -2.38375 -0.0070724 -0.00379547 0.13378 +EDGE3 128 178 5.83293 -0.00263856 -2.33337 0.00546661 0.00462911 0.00332802 +EDGE3 129 179 5.81781 0.0107309 -2.35394 0.0108488 0.00136009 -0.0110731 +EDGE3 128 177 5.42559 -5.0029 -2.26235 0.00325546 0.000287597 -0.121128 +EDGE3 129 178 5.3986 -5.01378 -2.30153 0.00772899 0.00358826 -0.133183 +EDGE3 128 179 5.62883 5.02037 -2.36585 0.00628176 -0.00336656 0.127019 +EDGE3 129 180 5.62222 5.05427 -2.395 -0.000759545 0.00199995 0.126886 +EDGE3 130 180 5.82184 -0.0197342 -2.3476 0.0089105 0.0107607 -0.00124023 +EDGE3 131 181 5.82193 -0.00619168 -2.34967 -0.00502768 -0.0027434 0.0030363 +EDGE3 130 179 5.3852 -5.04655 -2.30443 -0.00394044 0.00892445 -0.125781 +EDGE3 131 180 5.38776 -5.03624 -2.30596 -0.00103941 -0.0106571 -0.122426 +EDGE3 130 181 5.63674 5.05861 -2.41404 -0.00307442 -0.00909254 0.13335 +EDGE3 131 182 5.61802 5.08478 -2.39021 0.00111917 0.00326738 0.12637 +EDGE3 132 182 5.80975 -0.00613824 -2.36684 0.00222272 -0.00119453 0.00329392 +EDGE3 132 181 5.38875 -5.05656 -2.32502 -0.00816902 -0.0021291 -0.129809 +EDGE3 133 183 5.81899 0.0107705 -2.37083 -0.00303004 0.00172401 -0.000898821 +EDGE3 133 182 5.37904 -5.0875 -2.32445 0.000368746 -0.00195891 -0.125782 +EDGE3 132 183 5.59666 5.09276 -2.41657 -0.0102684 -0.00472247 0.123377 +EDGE3 133 184 5.61406 5.11065 -2.42405 0.000260489 0.00477785 0.123652 +EDGE3 134 184 5.82014 0.0127996 -2.39008 0.00164003 0.00871486 -0.00056987 +EDGE3 135 185 5.7891 -0.00198527 -2.3821 0.00319664 0.000327952 0.007284 +EDGE3 134 183 5.3817 -5.09477 -2.34226 0.00251445 0.00504492 -0.126381 +EDGE3 135 184 5.35712 -5.10464 -2.33129 -0.00470771 0.00446522 -0.120954 +EDGE3 134 185 5.61675 5.1262 -2.44749 0.00835458 0.00190111 0.120545 +EDGE3 135 186 5.58809 5.13123 -2.44386 0.00070762 -0.000931367 0.126615 +EDGE3 136 186 5.79541 0.00361309 -2.39212 0.000357085 0.00042635 0.00276907 +EDGE3 137 187 5.81003 0.0185833 -2.40675 0.00139138 -0.00433147 0.00672109 +EDGE3 136 185 5.38298 -5.13344 -2.34788 -0.00155289 0.000747263 -0.11945 +EDGE3 137 186 5.35682 -5.12205 -2.35757 -0.0012033 -0.00455866 -0.117761 +EDGE3 136 187 5.6083 5.13318 -2.44779 0.00291495 0.00845843 0.131367 +EDGE3 138 188 5.79736 0.00589466 -2.41443 0.00204346 -0.000325463 0.000341762 +EDGE3 137 188 5.58194 5.17677 -2.43977 -0.00257519 0.000312419 0.127528 +EDGE3 139 189 5.78926 0.00911122 -2.40126 -0.00567608 -0.00290277 0.00891849 +EDGE3 138 187 5.38927 -5.14813 -2.35346 -0.0060845 -0.000639396 -0.122968 +EDGE3 139 188 5.35467 -5.17133 -2.3692 0.00401004 -0.00905843 -0.116158 +EDGE3 138 189 5.58018 5.17467 -2.448 0.00454724 0.0047342 0.128385 +EDGE3 139 190 5.58665 5.20524 -2.47663 -0.0100811 -0.00283907 0.120983 +EDGE3 140 190 5.80184 0.000538131 -2.42515 0.00196545 -0.005324 -0.00618282 +EDGE3 141 191 5.77935 -0.00748809 -2.45042 -0.0100766 -0.00349617 0.00118143 +EDGE3 140 189 5.35874 -5.17083 -2.36919 0.000413041 0.000711537 -0.12565 +EDGE3 141 190 5.3628 -5.18387 -2.37445 -0.000241221 -0.00400845 -0.125639 +EDGE3 140 191 5.59494 5.20946 -2.47172 0.000885458 0.00429421 0.127445 +EDGE3 141 192 5.57286 5.21887 -2.49066 -0.000100917 -0.0021753 0.126676 +EDGE3 142 192 5.80576 0.0302671 -2.4382 -0.0128519 -0.00360723 -0.0048857 +EDGE3 143 193 5.77508 0.00394147 -2.42653 0.00841756 0.00135545 -0.0038313 +EDGE3 142 191 5.35462 -5.20314 -2.38674 0.000141457 -0.00282519 -0.128137 +EDGE3 143 192 5.3575 -5.23209 -2.38195 -0.00608188 -0.00444574 -0.1279 +EDGE3 142 193 5.56018 5.23833 -2.47906 -0.00176067 -0.00240263 0.125972 +EDGE3 143 194 5.56614 5.2335 -2.49796 0.00169487 -0.00732731 0.115616 +EDGE3 144 194 5.77143 0.00770613 -2.45164 -0.00417982 0.00866606 -0.00768732 +EDGE3 144 193 5.32936 -5.23967 -2.40444 0.000459216 0.00738128 -0.130647 +EDGE3 145 195 5.79225 0.0169204 -2.45245 -0.00110723 -0.00522928 -0.0065441 +EDGE3 144 195 5.58427 5.25898 -2.50291 0.0125382 -0.00764612 0.130573 +EDGE3 145 194 5.32872 -5.24648 -2.38929 -0.00193962 0.00760089 -0.129508 +EDGE3 146 196 5.77789 -0.00336557 -2.4744 0.00724279 -0.00414377 -0.00432928 +EDGE3 145 196 5.56039 5.28432 -2.5096 0.00611974 -0.00697688 0.123842 +EDGE3 146 195 5.3312 -5.27335 -2.40405 -0.00734407 0.000824763 -0.121347 +EDGE3 147 197 5.77977 -0.0183222 -2.48332 -0.00242465 -0.00601997 0.00309158 +EDGE3 146 197 5.54336 5.29048 -2.51322 0.00184973 -0.00380715 0.118812 +EDGE3 147 196 5.32505 -5.2783 -2.4143 -0.000803917 0.000159992 -0.124847 +EDGE3 148 198 5.77698 -0.017851 -2.48584 0.00878536 -0.00334252 0.00883341 +EDGE3 147 198 5.55894 5.29027 -2.53193 0.00615159 -0.000320007 0.129699 +EDGE3 148 197 5.32001 -5.28555 -2.41291 -0.00530757 0.000901927 -0.127068 +EDGE3 149 199 5.76686 0.0091611 -2.48136 -0.00112461 0.00922937 -0.00736067 +EDGE3 148 199 5.54112 5.31599 -2.54936 0.00127283 0.00621928 0.129475 +EDGE3 149 198 5.317 -5.32603 -2.4434 0.000883617 0.000357384 -0.125185 +EDGE3 150 200 5.7562 -0.0154595 -2.49467 0.00402636 0.00606298 -0.00307981 +EDGE3 149 200 5.54619 5.33972 -2.545 -0.00213811 0.0103017 0.120335 +EDGE3 150 199 5.32714 -5.35155 -2.45816 0.00825779 -0.00256778 -0.120056 +EDGE3 151 201 5.78054 -0.00882844 -2.49694 -0.000287276 0.0129323 -0.00473433 +EDGE3 151 200 5.31259 -5.34387 -2.43048 -0.00124561 -0.000855617 -0.124947 +EDGE3 150 201 5.52494 5.35234 -2.55254 0.00313984 0.00199059 0.117356 +EDGE3 152 202 5.75609 0.0207007 -2.51162 0.00560916 -0.00530332 0.00903449 +EDGE3 151 202 5.54255 5.36158 -2.56342 0.00674792 0.00302477 0.124916 +EDGE3 152 201 5.31184 -5.34705 -2.43526 -0.00452262 0.000654235 -0.126352 +EDGE3 153 203 5.75805 0.00540865 -2.50041 0.0012938 -0.00163891 0.00203313 +EDGE3 152 203 5.54515 5.37483 -2.57021 -0.00293532 -0.00979789 0.128554 +EDGE3 153 202 5.31332 -5.35592 -2.46136 -0.00738724 -0.00348712 -0.12721 +EDGE3 154 204 5.73889 0.0145687 -2.5206 0.00751353 0.00293891 0.00325345 +EDGE3 153 204 5.53425 5.3947 -2.5844 -0.00788534 0.00737028 0.126994 +EDGE3 154 203 5.28339 -5.37749 -2.465 -0.00539866 0.000686579 -0.119765 +EDGE3 155 205 5.74354 -0.00765853 -2.53338 0.000957149 0.00308731 0.00622773 +EDGE3 154 205 5.53481 5.40069 -2.58287 0.00474479 -0.0043952 0.121714 +EDGE3 155 204 5.31147 -5.40358 -2.46433 -0.00145406 -0.000207486 -0.121814 +EDGE3 156 206 5.74077 -0.0119403 -2.54469 0.00061614 0.0084617 0.00847225 +EDGE3 155 206 5.52356 5.41836 -2.59158 -0.0013559 -0.00207364 0.127637 +EDGE3 156 205 5.29464 -5.42748 -2.46362 -0.00409261 -0.00210303 -0.125072 +EDGE3 157 207 5.71651 -0.00650672 -2.55504 -0.00332362 0.00644226 -0.00308994 +EDGE3 156 207 5.51727 5.43027 -2.59884 0.000974606 -0.00750827 0.136223 +EDGE3 157 206 5.29194 -5.41319 -2.4781 -0.00651488 0.000944405 -0.131178 +EDGE3 158 208 5.75205 0.00809209 -2.55805 -0.00825876 0.00133194 0.000854928 +EDGE3 157 208 5.51073 5.44707 -2.59634 -0.00307028 0.00414619 0.132165 +EDGE3 158 207 5.28055 -5.42201 -2.51945 0.0143834 0.00474337 -0.126466 +EDGE3 159 209 5.74068 0.0112159 -2.56117 -0.0130545 -0.00430078 0.00384576 +EDGE3 158 209 5.51516 5.45878 -2.60055 0.00465947 -0.00295911 0.12412 +EDGE3 159 208 5.28139 -5.45586 -2.49098 0.00195884 0.00572952 -0.126633 +EDGE3 160 210 5.7346 -0.00654048 -2.56862 -0.00340003 -0.00199602 -0.00827291 +EDGE3 159 210 5.5014 5.4802 -2.61394 0.0040518 0.0033648 0.12103 +EDGE3 160 209 5.25612 -5.46358 -2.52297 -0.00231086 -0.00294848 -0.127605 +EDGE3 161 211 5.72575 0.0177602 -2.57482 -0.0034082 -0.00182098 -0.00139454 +EDGE3 160 211 5.51817 5.48953 -2.62701 0.00195526 0.00518635 0.128303 +EDGE3 161 210 5.27343 -5.48151 -2.51497 0.00501552 0.0015921 -0.126976 +EDGE3 162 212 5.73358 0.0190177 -2.59076 -0.00228277 0.0123627 0.00143952 +EDGE3 161 212 5.48375 5.50831 -2.63331 0.0046686 -0.00580639 0.114338 +EDGE3 162 211 5.27359 -5.50173 -2.52515 -0.00441229 0.00110085 -0.124214 +EDGE3 163 213 5.7196 0.00824366 -2.59774 0.00226308 -0.00134595 -0.00683796 +EDGE3 162 213 5.48007 5.50722 -2.63511 0.00763833 -0.00777952 0.121173 +EDGE3 163 212 5.26056 -5.50537 -2.53088 -0.00277407 0.00230028 -0.126173 +EDGE3 164 214 5.72237 -0.00825224 -2.60969 -0.00467588 0.00329792 0.00711357 +EDGE3 163 214 5.50375 5.52481 -2.64868 0.00249999 0.00549918 0.126665 +EDGE3 164 213 5.2569 -5.52079 -2.54529 0.00327059 0.00101119 -0.123196 +EDGE3 165 215 5.72991 -0.0130351 -2.5836 -0.00978211 -0.0011212 0.00170482 +EDGE3 164 215 5.49594 5.54304 -2.65036 -0.00534129 -0.0026147 0.13013 +EDGE3 165 214 5.25512 -5.53692 -2.56244 0.00260399 -0.00068308 -0.128689 +EDGE3 166 216 5.72393 0.00368218 -2.61628 -0.00249097 -0.00558572 -0.00384151 +EDGE3 165 216 5.48351 5.54018 -2.67681 0.000854679 0.00436414 0.1246 +EDGE3 166 215 5.2473 -5.55196 -2.55502 -0.00141156 0.0169631 -0.123119 +EDGE3 167 217 5.71272 -0.00628011 -2.63087 -0.00778733 0.00157421 -0.00626345 +EDGE3 166 217 5.47304 5.56926 -2.68068 0.00348615 0.00837144 0.123796 +EDGE3 167 216 5.23987 -5.5691 -2.55701 -0.00190647 0.00977801 -0.129046 +EDGE3 168 218 5.70121 -0.00460123 -2.62326 0.000227827 0.00622522 0.00416443 +EDGE3 167 218 5.45772 5.60375 -2.67494 -4.5013e-05 0.00640296 0.132244 +EDGE3 168 217 5.24754 -5.58352 -2.56321 -0.00692286 -0.0018102 -0.11982 +EDGE3 169 219 5.71504 0.00203965 -2.62734 -0.00107923 0.00261847 0.000539422 +EDGE3 168 219 5.457 5.59963 -2.68502 -0.00283424 0.00742396 0.12701 +EDGE3 169 218 5.21433 -5.60481 -2.59877 0.00507696 -0.00992058 -0.12887 +EDGE3 170 220 5.69518 0.00930935 -2.64097 -0.00103116 -0.00557348 -0.00195959 +EDGE3 170 219 5.24638 -5.60682 -2.56982 0.0038678 0.00454005 -0.125142 +EDGE3 169 220 5.47585 5.61079 -2.68439 0.000463241 -0.00263866 0.125312 +EDGE3 171 221 5.70022 -0.00497816 -2.64524 0.00272628 0.00127152 0.00289555 +EDGE3 170 221 5.45848 5.63214 -2.69054 -0.000947434 0.000958733 0.133475 +EDGE3 171 220 5.24227 -5.61745 -2.56936 -0.0118452 -0.0013965 -0.127175 +EDGE3 172 222 5.70163 0.00875117 -2.64296 -0.00151686 0.000839614 0.00432467 +EDGE3 171 222 5.45007 5.6618 -2.70671 0.00373858 -0.00382736 0.130612 +EDGE3 172 221 5.2198 -5.62542 -2.59758 0.000117031 0.00154721 -0.130821 +EDGE3 173 223 5.70108 -0.0203346 -2.6379 0.000717357 -0.00398153 0.00405844 +EDGE3 172 223 5.44212 5.64459 -2.70345 0.00955057 0.00523261 0.11973 +EDGE3 173 222 5.21552 -5.63644 -2.61464 -0.00394663 0.00938608 -0.11797 +EDGE3 174 224 5.69039 -0.00934215 -2.65729 -0.000636047 -0.00450725 0.000571352 +EDGE3 174 223 5.21741 -5.64529 -2.61793 0.00631962 -0.00259502 -0.130891 +EDGE3 173 224 5.44203 5.66903 -2.71401 -0.00321256 -0.000206332 0.137264 +EDGE3 175 225 5.69836 0.00360652 -2.65019 0.00127774 -0.00418832 0.000661435 +EDGE3 174 225 5.44863 5.68978 -2.70313 -0.000271414 0.00219224 0.123585 +EDGE3 175 224 5.20348 -5.67623 -2.60925 -0.000610676 -0.00074851 -0.121645 +EDGE3 176 226 5.68978 -0.00123422 -2.69126 -0.00717981 -0.00105451 0.00195912 +EDGE3 175 226 5.44649 5.69959 -2.74264 0.0133318 0.0061567 0.118429 +EDGE3 176 225 5.21033 -5.7009 -2.61975 0.00234792 0.00133415 -0.130126 +EDGE3 177 227 5.67134 -0.00980794 -2.69715 0.00127255 -0.00161092 -0.00123338 +EDGE3 176 227 5.43597 5.70907 -2.74674 -0.000553111 -0.000999087 0.130047 +EDGE3 177 226 5.20948 -5.68986 -2.61937 0.00111188 0.00321067 -0.122676 +EDGE3 178 228 5.66137 -0.0200877 -2.69106 0.00112623 0.00834103 0.00498475 +EDGE3 177 228 5.42161 5.73674 -2.74592 -0.00641124 -0.00859996 0.126995 +EDGE3 178 227 5.18563 -5.71411 -2.62773 0.00864731 -0.00125788 -0.114085 +EDGE3 179 229 5.67355 -0.00540887 -2.68706 -0.00464168 0.00517855 -0.00187282 +EDGE3 178 229 5.40338 5.75353 -2.75046 -0.00191577 -0.00524981 0.127282 +EDGE3 179 228 5.18759 -5.72278 -2.64526 -0.00204173 0.00247132 -0.122487 +EDGE3 180 230 5.69332 -0.00345162 -2.70496 0.00253649 0.000832369 0.00587571 +EDGE3 179 230 5.41995 5.75862 -2.75012 0.00271393 0.00453144 0.142366 +EDGE3 180 229 5.18813 -5.74585 -2.66121 -0.00219612 -0.00200361 -0.124176 +EDGE3 181 231 5.65998 -0.00810357 -2.71726 -0.00357751 0.00127123 1.82223e-05 +EDGE3 180 231 5.41895 5.76476 -2.77408 -0.00143302 -0.00145822 0.129515 +EDGE3 181 230 5.18537 -5.76176 -2.65636 -0.00572485 -0.00482494 -0.119443 +EDGE3 182 232 5.6555 -0.000193813 -2.72322 -0.000258984 -0.00637001 -0.00179685 +EDGE3 181 232 5.42787 5.80761 -2.77927 -0.0134134 -0.00287348 0.125778 +EDGE3 182 231 5.19673 -5.77472 -2.64873 0.000315872 -0.00779232 -0.119268 +EDGE3 183 233 5.66419 0.00508272 -2.72413 -0.00371601 0.00120713 -0.00333641 +EDGE3 182 233 5.39168 5.77913 -2.77211 0.00474791 0.00260123 0.124428 +EDGE3 183 232 5.17485 -5.79618 -2.66991 0.00180784 -0.00967104 -0.127362 +EDGE3 184 234 5.66085 -0.00547281 -2.73169 0.000748645 0.00208808 -0.000860597 +EDGE3 183 234 5.40112 5.82406 -2.7974 -0.00307088 -7.13772e-05 0.120616 +EDGE3 184 233 5.17831 -5.80262 -2.66754 -0.00129222 0.00356908 -0.134378 +EDGE3 185 235 5.65732 -0.0109558 -2.75635 0.00711419 -0.00547322 0.00179182 +EDGE3 184 235 5.408 5.80065 -2.79951 -0.0157253 0.00704819 0.120861 +EDGE3 185 234 5.17799 -5.81957 -2.68761 -0.00426062 0.00366648 -0.130818 +EDGE3 186 236 5.63339 -0.00827312 -2.751 -0.0110922 -0.00508354 0.00149513 +EDGE3 185 236 5.39281 5.8531 -2.7987 -0.00345573 -0.00997029 0.119619 +EDGE3 186 235 5.16738 -5.83473 -2.68695 0.000416481 -0.00173212 -0.129461 +EDGE3 187 237 5.64776 -0.00336791 -2.75866 0.00160899 -0.00910978 0.000928463 +EDGE3 186 237 5.36833 5.84313 -2.80863 0.00555427 0.00434125 0.130482 +EDGE3 187 236 5.1528 -5.82917 -2.72503 0.0100905 0.00357962 -0.124625 +EDGE3 188 238 5.63081 -0.00243124 -2.77045 -0.00100979 0.00118096 0.0133921 +EDGE3 187 238 5.36261 5.85505 -2.79953 -0.00178385 0.00280293 0.131339 +EDGE3 188 237 5.16046 -5.83338 -2.71593 -0.00340923 0.00177035 -0.128438 +EDGE3 189 239 5.63011 -0.016553 -2.7844 0.0107624 -0.00286546 -0.00631263 +EDGE3 188 239 5.36853 5.90386 -2.81748 -0.0050575 0.00869306 0.121246 +EDGE3 189 238 5.14754 -5.87156 -2.72027 -0.000969913 -0.00172586 -0.126021 +EDGE3 190 240 5.64259 -0.0100221 -2.77632 -0.00174618 -0.00463429 -0.00188685 +EDGE3 189 240 5.37916 5.89146 -2.84064 -0.0014954 -0.0025996 0.128553 +EDGE3 190 239 5.14504 -5.89497 -2.71144 0.00247667 0.00410107 -0.126566 +EDGE3 191 241 5.62879 -0.00464936 -2.78458 -0.00459359 0.00292511 0.00245095 +EDGE3 190 241 5.37454 5.90749 -2.83379 0.00509864 -0.0059042 0.129645 +EDGE3 191 240 5.14542 -5.89809 -2.74901 0.0143751 -0.00870689 -0.133753 +EDGE3 192 242 5.63009 0.00531532 -2.80406 0.00787219 -0.00177989 0.00123312 +EDGE3 191 242 5.36499 5.92451 -2.85593 0.00461249 0.00361625 0.119002 +EDGE3 192 241 5.13355 -5.92388 -2.71278 -0.00918494 -0.00523815 -0.126294 +EDGE3 193 243 5.62665 -0.00965967 -2.8014 0.000585478 -0.00562915 0.000450034 +EDGE3 192 243 5.36466 5.92768 -2.84473 -0.00714825 0.00493181 0.125106 +EDGE3 193 242 5.14747 -5.91789 -2.74535 -0.00370175 -0.00237716 -0.13104 +EDGE3 194 244 5.63572 0.01122 -2.82287 -0.00797533 0.00243817 0.00184757 +EDGE3 193 244 5.36441 5.96056 -2.85979 -0.00634215 0.00270466 0.116885 +EDGE3 195 245 5.61037 -0.00287581 -2.80848 0.00370576 0.00165629 -0.00459601 +EDGE3 194 243 5.15 -5.96628 -2.77125 0.00486761 0.000542237 -0.130749 +EDGE3 194 245 5.33819 5.97826 -2.86999 -0.00118042 -0.0050262 0.128895 +EDGE3 196 246 5.59853 0.00338405 -2.84012 -0.00309265 -0.00373368 0.00553647 +EDGE3 195 244 5.10975 -5.96687 -2.7689 0.00289216 -0.00705341 -0.126488 +EDGE3 196 245 5.12115 -5.9743 -2.77164 -0.00117539 -0.00473617 -0.127642 +EDGE3 195 246 5.36587 5.984 -2.87861 0.00186173 -0.00867208 0.11747 +EDGE3 197 247 5.60996 -0.00820362 -2.82718 -0.000610771 -0.00674931 -0.00443733 +EDGE3 196 247 5.35493 6.00578 -2.88822 0.00392779 -0.00854464 0.129236 +EDGE3 198 248 5.60029 0.0122551 -2.83963 -0.00254273 0.00714214 0.000587309 +EDGE3 197 246 5.13501 -5.99738 -2.77946 -0.0110365 -0.000454168 -0.123331 +EDGE3 198 247 5.10253 -5.99341 -2.79447 0.00101249 0.00453254 -0.130104 +EDGE3 197 248 5.34015 6.00182 -2.89708 -0.0019431 0.00629643 0.133357 +EDGE3 198 249 5.35092 6.0355 -2.91745 0.00405763 0.00356624 0.126799 +EDGE3 199 249 5.60055 0.0125382 -2.82653 -0.00354375 -0.00320807 -0.00139164 +EDGE3 199 248 5.10305 -6.01506 -2.79044 0.00214552 6.39272e-05 -0.124024 +EDGE3 200 250 5.61108 0.0148192 -2.85084 0.00431736 -0.000337999 0.00663123 +EDGE3 200 249 5.10449 -6.01133 -2.79246 0.000521379 -3.96923e-05 -0.121528 +EDGE3 199 250 5.3292 6.02936 -2.90527 0.00106622 -0.00643111 0.128582 +EDGE3 201 251 5.59013 -0.00743196 -2.84857 0.00884108 3.53843e-05 -0.00617016 +EDGE3 200 251 5.32704 6.05258 -2.91027 -0.00483897 -0.00292767 0.129554 +EDGE3 201 250 5.09882 -6.0268 -2.79962 -0.0159607 0.00315331 -0.126483 +EDGE3 201 252 5.33098 6.07238 -2.91037 0.00611606 -9.06802e-05 0.130136 +EDGE3 202 252 5.59485 0.0223155 -2.87135 0.00362976 -0.00414064 0.00110163 +EDGE3 203 253 5.57936 0.00148591 -2.86545 0.0058263 0.00610799 -0.00151249 +EDGE3 202 251 5.10549 -6.03476 -2.80909 0.000135952 0.0101902 -0.129256 +EDGE3 203 252 5.09386 -6.0599 -2.82043 0.00437412 0.00860174 -0.11976 +EDGE3 202 253 5.29822 6.05526 -2.92252 0.00574996 0.00447968 0.11807 +EDGE3 204 254 5.58725 -0.00510351 -2.86338 0.000148867 -0.00348714 0.00212196 +EDGE3 203 254 5.31183 6.0851 -2.93827 0.000826606 -0.0048196 0.124139 +EDGE3 205 255 5.57885 -0.00433947 -2.88398 0.00549276 -0.00418488 0.00475266 +EDGE3 204 253 5.08788 -6.08477 -2.81308 0.00541816 0.00176208 -0.124587 +EDGE3 205 254 5.0803 -6.1029 -2.82673 -0.00443602 0.000346991 -0.124026 +EDGE3 204 255 5.30828 6.08365 -2.93019 -0.000700436 -0.000691011 0.126474 +EDGE3 205 256 5.31297 6.13163 -2.96506 -0.000856499 -0.00833334 0.124964 +EDGE3 206 256 5.58503 0.0122368 -2.89086 -0.000861996 -0.00489995 0.0009036 +EDGE3 207 257 5.56001 9.14398e-05 -2.91083 -0.00258294 0.00309321 -0.000812676 +EDGE3 206 255 5.07222 -6.09691 -2.84323 -0.0032043 -0.00320701 -0.127916 +EDGE3 206 257 5.29863 6.13298 -2.96111 -0.00322059 -0.00163801 0.125651 +EDGE3 207 256 5.07736 -6.12617 -2.83147 0.00613326 0.00679253 -0.122377 +EDGE3 207 258 5.28533 6.15371 -2.97314 -0.00133849 0.00624459 0.130432 +EDGE3 208 258 5.55821 0.00895179 -2.91072 -0.0128322 0.000915018 -0.00665918 +EDGE3 209 259 5.56868 -0.00413472 -2.91323 0.000282983 -0.00697001 -0.00342294 +EDGE3 208 257 5.07548 -6.12852 -2.846 0.00261474 0.00561432 -0.125376 +EDGE3 208 259 5.28839 6.1554 -2.9542 -0.00392393 -0.00778073 0.131669 +EDGE3 209 258 5.05838 -6.16122 -2.84819 0.00245423 -0.00420368 -0.124412 +EDGE3 209 260 5.27432 6.1859 -2.96895 0.000307793 -0.00429792 0.132774 +EDGE3 210 260 5.56595 0.00504558 -2.91542 0.0012642 -0.000508167 0.00544831 +EDGE3 211 261 5.56176 -0.0079744 -2.93077 -0.00129557 0.00120963 0.00600065 +EDGE3 210 259 5.07906 -6.15475 -2.84731 0.00300364 -0.00938758 -0.128453 +EDGE3 211 260 5.06219 -6.17201 -2.87906 -0.00388378 0.00904707 -0.114292 +EDGE3 210 261 5.28844 6.18448 -2.99247 -0.00524846 0.00301783 0.126769 +EDGE3 211 262 5.2774 6.20065 -2.98696 -0.00209432 -0.00726245 0.126899 +EDGE3 212 262 5.55368 0.000175569 -2.94276 0.00878515 -0.00738728 0.00067105 +EDGE3 213 263 5.55803 -0.00222484 -2.94365 0.000236606 0.0031112 -0.00343774 +EDGE3 212 261 5.04849 -6.18763 -2.87176 -0.00396174 0.00405756 -0.122846 +EDGE3 213 262 5.06431 -6.20803 -2.87011 0.000843709 -0.002089 -0.119412 +EDGE3 212 263 5.27038 6.19767 -2.99379 0.010667 -0.00100277 0.137248 +EDGE3 213 264 5.27209 6.22609 -3.00736 -0.00662612 0.00104638 0.130947 +EDGE3 214 264 5.55302 -0.00500383 -2.93615 0.00471031 -0.00881772 0.00642843 +EDGE3 215 265 5.54275 0.00531179 -2.94492 0.00873938 -0.00174286 0.0102921 +EDGE3 214 263 5.05181 -6.22121 -2.87762 -0.0139794 0.00302457 -0.134358 +EDGE3 215 264 5.03688 -6.22165 -2.89924 -0.00473188 -0.00460084 -0.127016 +EDGE3 214 265 5.25292 6.24884 -3.01057 0.00213821 -0.00652799 0.134767 +EDGE3 216 266 5.52208 -0.00370182 -2.97737 0.00112232 -0.000181451 -0.00298144 +EDGE3 215 266 5.26674 6.26503 -3.02364 -0.00116255 0.00601984 0.126746 +EDGE3 216 265 5.03912 -6.23766 -2.90235 0.000180229 -0.00507376 -0.123458 +EDGE3 216 267 5.24678 6.25859 -3.0123 0.00109594 -0.00296084 0.128649 +EDGE3 217 267 5.5394 0.00415257 -2.97904 -0.0042656 -0.00178282 -0.000774338 +EDGE3 218 268 5.5361 -0.00767141 -2.98703 -0.00802583 0.00152106 -0.00320633 +EDGE3 217 266 5.01901 -6.25615 -2.92064 -0.00265829 0.00387811 -0.121482 +EDGE3 218 267 5.01934 -6.2443 -2.89251 -0.00341205 -0.0150605 -0.122031 +EDGE3 217 268 5.24232 6.30096 -3.01367 0.00467514 -0.000390222 0.121208 +EDGE3 218 269 5.25249 6.29153 -3.03227 0.00443477 0.00387701 0.121538 +EDGE3 219 269 5.53548 -0.0176421 -2.97731 -0.00451322 0.0132581 -0.00185255 +EDGE3 220 270 5.52213 -0.00648808 -2.97925 0.00475388 -0.00398332 -0.00995929 +EDGE3 219 268 5.03248 -6.29704 -2.93069 0.00225453 0.00289403 -0.131234 +EDGE3 219 270 5.23215 6.31914 -3.05329 -0.00605935 5.72982e-05 0.131995 +EDGE3 220 269 5.0022 -6.3138 -2.93078 0.00720007 -0.00682822 -0.127204 +EDGE3 220 271 5.23822 6.33092 -3.05399 -0.000412335 0.000605746 0.127995 +EDGE3 221 271 5.51517 -0.0111389 -3.01277 0.0112763 0.00356529 0.00505068 +EDGE3 222 272 5.50915 0.0139361 -3.0059 -0.00835159 0.00192785 0.00690006 +EDGE3 221 270 5.03219 -6.30839 -2.94352 -0.0124484 -0.000292667 -0.118497 +EDGE3 222 271 5.01615 -6.33414 -2.94146 0.00203755 -0.00101235 -0.129842 +EDGE3 221 272 5.23123 6.34195 -3.06182 0.00242542 -0.00446925 0.116497 +EDGE3 223 273 5.52075 -0.000149756 -2.99993 0.000604763 -0.0023122 -0.00311226 +EDGE3 222 273 5.21833 6.34143 -3.07122 -0.00274573 0.00349874 0.130513 +EDGE3 223 272 4.99842 -6.33582 -2.96008 0.00441995 -0.00493651 -0.124767 +EDGE3 223 274 5.20621 6.37323 -3.05518 0.00563142 -0.0025157 0.12439 +EDGE3 224 274 5.51417 0.0119246 -3.03344 0.00602365 0.00117234 0.00331348 +EDGE3 224 273 4.99645 -6.37092 -2.95012 -0.00117516 0.00511441 -0.128256 +EDGE3 225 275 5.50899 -0.00326492 -3.03087 0.00360157 -0.00308821 -0.00714632 +EDGE3 224 275 5.22473 6.38433 -3.06505 -0.00105509 -0.00549735 0.130124 +EDGE3 226 276 5.50797 0.00743388 -3.01963 -0.00366911 -0.0145918 -0.00243786 +EDGE3 225 274 4.99643 -6.38092 -2.96137 -0.0017886 0.00106681 -0.125539 +EDGE3 226 275 5.00093 -6.38836 -2.96633 0.00338015 -0.000891871 -0.130143 +EDGE3 225 276 5.21574 6.39248 -3.08528 -0.0104843 -0.00890487 0.127159 +EDGE3 226 277 5.20909 6.40337 -3.10033 -0.00108852 0.00449258 0.12618 +EDGE3 227 277 5.50744 0.00638313 -3.03994 -0.0036519 0.000757313 -0.00365164 +EDGE3 228 278 5.49568 -0.00932806 -3.04432 -0.00749447 -0.00154948 -0.0012305 +EDGE3 227 276 4.97242 -6.41141 -2.97669 0.000787533 -0.00267261 -0.125722 +EDGE3 228 277 4.99585 -6.41104 -2.97534 -0.0028433 0.00250345 -0.116276 +EDGE3 227 278 5.2025 6.42396 -3.0974 -0.0050579 -0.00257609 0.131659 +EDGE3 228 279 5.20794 6.43943 -3.0991 -0.00350462 -0.00151308 0.132775 +EDGE3 229 279 5.48364 0.000510246 -3.05345 0.00331325 0.00102331 0.00115266 +EDGE3 230 280 5.48863 0.000603872 -3.05648 0.00621932 0.00438185 0.00958958 +EDGE3 229 278 4.9821 -6.43921 -2.99879 0.000608137 -0.0063293 -0.120215 +EDGE3 230 279 4.96582 -6.43688 -2.98534 -0.0013785 -0.00175749 -0.123104 +EDGE3 229 280 5.17877 6.45871 -3.11832 0.00132879 0.00209826 0.127745 +EDGE3 230 281 5.18267 6.46019 -3.1171 0.00359102 0.000175126 0.13148 +EDGE3 231 281 5.49012 -0.01805 -3.05803 0.00542177 0.00968785 -0.0119625 +EDGE3 231 280 4.96542 -6.44952 -3.00274 0.00265113 0.000552572 -0.130552 +EDGE3 232 282 5.48304 0.00226914 -3.07471 0.00216862 -0.00128414 -0.000708762 +EDGE3 231 282 5.1718 6.46288 -3.1307 0.0114639 -0.00524814 0.127516 +EDGE3 232 281 4.95523 -6.47165 -3.03276 0.00356974 -0.00658082 -0.114928 +EDGE3 233 283 5.47151 0.00100731 -3.08639 -0.0020429 -0.00394253 0.00338911 +EDGE3 232 283 5.1799 6.48219 -3.14791 -0.00446491 0.00429073 0.122212 +EDGE3 233 282 4.96438 -6.47367 -3.00375 0.000178466 -0.00192541 -0.129065 +EDGE3 234 284 5.46797 0.0132731 -3.08858 -0.00559802 -0.00491985 -0.00424409 +EDGE3 233 284 5.18676 6.48371 -3.15208 0.00766089 0.00969444 0.122728 +EDGE3 234 283 4.96279 -6.48527 -3.00584 -0.00383465 -0.00182908 -0.123567 +EDGE3 235 285 5.45026 -0.0169477 -3.10045 -0.00603362 0.00191477 -0.00372417 +EDGE3 234 285 5.15661 6.51284 -3.14055 -0.00747502 -0.00693036 0.1287 +EDGE3 235 284 4.95194 -6.51282 -3.02818 0.00662871 -5.03283e-05 -0.121361 +EDGE3 236 286 5.47475 -0.00740574 -3.12291 -0.00225724 -0.0117553 -0.0116044 +EDGE3 235 286 5.16413 6.51527 -3.157 -0.00155674 -0.00398257 0.118644 +EDGE3 236 285 4.94357 -6.52696 -3.04901 -0.00195743 0.00716524 -0.125696 +EDGE3 237 287 5.4811 0.00665819 -3.10516 -0.0012375 -0.00165195 -0.00364606 +EDGE3 236 287 5.15673 6.54727 -3.16333 -0.00244503 0.0145701 0.12535 +EDGE3 237 286 4.94121 -6.50855 -3.04845 -0.00476196 -0.00169207 -0.112113 +EDGE3 238 288 5.44787 0.00394819 -3.12036 0.00319991 -0.00605266 0.00219998 +EDGE3 237 288 5.15877 6.55326 -3.18741 0.0031107 0.0122362 0.126034 +EDGE3 238 287 4.93341 -6.53205 -3.04272 0.00194695 -0.00179728 -0.123819 +EDGE3 239 289 5.45817 0.0111234 -3.1138 0.000512803 -0.00440063 0.000583011 +EDGE3 238 289 5.16256 6.56148 -3.19757 0.00353602 -0.00057207 0.129761 +EDGE3 239 288 4.93501 -6.54121 -3.05213 -0.00126133 -0.00420166 -0.124097 +EDGE3 240 290 5.45053 0.0100044 -3.11913 -0.00411782 -0.000976444 1.80109e-05 +EDGE3 239 290 5.152 6.57817 -3.19872 0.00514163 0.000206234 0.120737 +EDGE3 240 289 4.92825 -6.56288 -3.07441 0.0032601 0.00374743 -0.132422 +EDGE3 241 291 5.43166 0.00862436 -3.11926 0.00406577 -0.00437004 -0.000551912 +EDGE3 240 291 5.1338 6.59208 -3.19954 0.00766373 0.00402098 0.13595 +EDGE3 241 290 4.93627 -6.58294 -3.06661 0.00155676 0.00402179 -0.123722 +EDGE3 242 292 5.44055 -0.00486903 -3.1404 -0.00392076 0.0074179 0.000731179 +EDGE3 242 291 4.93016 -6.57527 -3.09318 -0.00316706 0.000666799 -0.126481 +EDGE3 241 292 5.15313 6.61836 -3.20155 -0.00116943 -0.003175 0.12135 +EDGE3 243 293 5.42508 -0.00934516 -3.13597 0.00476955 0.00663805 -0.00659988 +EDGE3 242 293 5.13859 6.60634 -3.2321 0.000278645 0.00167672 0.130864 +EDGE3 244 294 5.40892 -0.0107356 -3.1453 0.00270068 0.00333384 0.00760643 +EDGE3 243 292 4.92586 -6.62206 -3.09261 0.00202214 0.00119654 -0.12575 +EDGE3 243 294 5.12524 6.63455 -3.22126 0.00828426 0.0013328 0.129956 +EDGE3 244 293 4.9088 -6.62136 -3.08311 -0.00164893 0.00223169 -0.127986 +EDGE3 245 295 5.42048 0.0057147 -3.15328 0.00803038 0.00240249 0.00844143 +EDGE3 244 295 5.11159 6.6501 -3.21226 -0.000550698 -0.00185667 0.124658 +EDGE3 245 294 4.88823 -6.63876 -3.10817 -0.00679315 0.00292588 -0.121018 +EDGE3 246 296 5.42161 0.0153014 -3.17534 0.00593621 -0.00537435 -0.00926714 +EDGE3 245 296 5.09949 6.66048 -3.22853 0.00916531 -0.00413916 0.122669 +EDGE3 246 295 4.90635 -6.62889 -3.11324 0.0021014 0.00136475 -0.129371 +EDGE3 247 297 5.4263 -0.00877355 -3.18383 0.00238451 -0.00290521 0.000257543 +EDGE3 246 297 5.09639 6.68724 -3.22701 0.00787618 0.000947643 0.1243 +EDGE3 247 296 4.87912 -6.66273 -3.11925 -0.000130779 -0.00151923 -0.130224 +EDGE3 248 298 5.43265 -0.00434997 -3.18155 0.00182059 -0.00168597 0.00618919 +EDGE3 247 298 5.0927 6.69043 -3.23346 0.00244651 0.00213085 0.131549 +EDGE3 248 297 4.88172 -6.68042 -3.12005 0.00651999 -0.000336627 -0.134107 +EDGE3 249 299 5.40456 0.0151498 -3.20193 0.00277883 0.00570035 0.00336773 +EDGE3 248 299 5.0888 6.69792 -3.24818 -0.000177389 -0.00198716 0.123436 +EDGE3 249 298 4.88239 -6.69162 -3.10618 -0.0112478 0.00251019 -0.126545 +EDGE3 250 300 5.39933 0.00813087 -3.21225 -0.00297852 0.0048837 0.00600314 +EDGE3 249 300 5.09878 6.72075 -3.25086 0.0106186 0.00020785 0.126653 +EDGE3 250 299 4.89959 -6.69853 -3.13103 -0.000412611 0.000196737 -0.123394 +EDGE3 251 301 5.41067 0.00083568 -3.21539 0.000496562 0.000990227 0.000837513 +EDGE3 251 300 4.85693 -6.71508 -3.13652 -0.00281962 -0.00385658 -0.127052 +EDGE3 250 301 5.09008 6.72705 -3.25139 0.00742812 0.0029925 0.126313 +EDGE3 252 302 5.39622 -0.00538103 -3.17504 0.00297166 -0.000514373 -0.00139814 +EDGE3 251 302 5.1135 6.73372 -3.27022 -0.00170259 -0.000376412 0.119803 +EDGE3 252 301 4.85995 -6.72822 -3.14297 0.00750694 -0.00570432 -0.127131 +EDGE3 253 303 5.39368 -0.0021081 -3.22232 0.000475584 -0.00755415 -0.000627045 +EDGE3 252 303 5.08017 6.74682 -3.26979 -0.00158622 -0.00401124 0.127568 +EDGE3 253 302 4.87687 -6.73723 -3.17254 -0.00164508 -0.00218044 -0.127781 +EDGE3 254 304 5.37352 0.0205802 -3.22174 0.0067146 0.00482225 0.00342044 +EDGE3 253 304 5.05817 6.77577 -3.28736 -0.00182185 -0.00175093 0.131061 +EDGE3 254 303 4.86381 -6.7623 -3.17046 0.00231894 -0.00440473 -0.120624 +EDGE3 255 305 5.38145 -0.00345948 -3.23045 -0.0027773 0.00250695 -0.00174968 +EDGE3 254 305 5.07976 6.78685 -3.29042 -0.00333686 -0.0130463 0.133745 +EDGE3 255 304 4.8569 -6.78377 -3.16787 0.00567279 0.000501424 -0.126119 +EDGE3 256 306 5.38497 0.0182302 -3.23946 0.0026426 -0.000784359 -0.00626292 +EDGE3 255 306 5.075 6.79204 -3.29428 0.00342846 -0.00262557 0.123821 +EDGE3 256 305 4.82759 -6.78633 -3.17726 0.00592224 -0.007314 -0.126964 +EDGE3 257 307 5.3813 -0.000308903 -3.24652 -0.00948695 -0.00906708 0.00157051 +EDGE3 257 306 4.83632 -6.79318 -3.18393 0.00438808 0.00194382 -0.12117 +EDGE3 256 307 5.07909 6.80204 -3.30585 -0.00150696 -0.000897198 0.127209 +EDGE3 258 308 5.36728 0.00137117 -3.25205 0.00758383 -0.00227775 -0.00345179 +EDGE3 257 308 5.03753 6.82899 -3.33468 -0.00235691 -0.000669521 0.120767 +EDGE3 258 307 4.84409 -6.82378 -3.19449 -0.00705895 -0.00271906 -0.127771 +EDGE3 259 309 5.36424 0.00554813 -3.25916 -0.00616131 0.00551423 0.000323097 +EDGE3 258 309 5.05077 6.83824 -3.31713 -0.00460874 0.00397837 0.114516 +EDGE3 259 308 4.83782 -6.82686 -3.20179 0.00344517 0.000880065 -0.125318 +EDGE3 260 310 5.38082 -0.00443584 -3.26877 -0.00106722 0.00233864 0.00383481 +EDGE3 259 310 5.05586 6.85435 -3.33275 -0.00720592 -0.00435552 0.133339 +EDGE3 260 309 4.82717 -6.82137 -3.19145 0.00203539 0.0125647 -0.116785 +EDGE3 261 311 5.36926 -0.00650657 -3.26492 -0.000120723 -0.000841319 0.00735514 +EDGE3 260 311 5.05391 6.86216 -3.33276 -0.00228272 0.00774138 0.128304 +EDGE3 261 310 4.81866 -6.85119 -3.20953 0.00227368 0.00664809 -0.122443 +EDGE3 262 312 5.35635 -0.00282258 -3.24847 -0.00412182 -0.000169067 -0.00461352 +EDGE3 261 312 5.03066 6.88057 -3.33992 0.00300346 -0.0137782 0.12509 +EDGE3 262 311 4.81763 -6.86299 -3.20588 0.00155772 -0.00481732 -0.120012 +EDGE3 263 313 5.3372 -0.0158583 -3.30367 -8.60871e-05 0.00126905 -0.00124473 +EDGE3 262 313 5.04164 6.87276 -3.33733 0.00595866 -5.70527e-06 0.131523 +EDGE3 263 312 4.82521 -6.88601 -3.21523 0.000763975 0.00836663 -0.123322 +EDGE3 264 314 5.34177 0.000814248 -3.29855 -0.00268505 0.000753952 -0.0010966 +EDGE3 263 314 5.02236 6.90389 -3.34336 0.0106759 -0.00589425 0.128413 +EDGE3 264 313 4.80602 -6.89411 -3.21239 0.00501782 0.00111687 -0.131643 +EDGE3 265 315 5.3413 -0.00959307 -3.2901 -0.00223825 0.00146348 -0.00307337 +EDGE3 264 315 5.00667 6.91518 -3.35169 -0.0055706 0.00241409 0.122952 +EDGE3 265 314 4.81887 -6.91634 -3.22234 -0.00122376 -0.000212156 -0.128928 +EDGE3 266 316 5.34154 -0.00288012 -3.32434 -0.00869203 0.00252905 -0.00442364 +EDGE3 265 316 5.01078 6.92099 -3.36775 0.00169323 -0.0120643 0.127417 +EDGE3 266 315 4.80356 -6.90957 -3.2431 -0.00664684 -3.36993e-05 -0.122999 +EDGE3 267 317 5.32999 -0.00642501 -3.31268 0.00160127 -0.00525228 0.0100557 +EDGE3 266 317 5.01756 6.93346 -3.37179 0.00453221 0.00528213 0.129261 +EDGE3 267 316 4.77767 -6.92316 -3.23968 0.00645285 0.00987134 -0.120023 +EDGE3 268 318 5.34975 0.0122049 -3.32866 0.00232917 -0.00111033 -0.00212467 +EDGE3 267 318 5.01399 6.94519 -3.37089 -0.00491123 0.00203469 0.124224 +EDGE3 268 317 4.78893 -6.93772 -3.25043 0.00382879 0.00530138 -0.130831 +EDGE3 269 319 5.32472 -0.0034687 -3.31924 5.51239e-05 -0.000242999 -0.00362235 +EDGE3 268 319 5.00354 6.95292 -3.40433 -0.00419935 0.00393593 0.132912 +EDGE3 269 318 4.78472 -6.95715 -3.24832 0.00965665 0.00799651 -0.12045 +EDGE3 270 320 5.32618 0.00888813 -3.35734 0.00239 -0.000225544 0.00188561 +EDGE3 269 320 4.99824 6.96473 -3.40227 0.00536281 0.00450597 0.122742 +EDGE3 270 319 4.77086 -6.97035 -3.26716 0.00976577 -0.00306358 -0.128053 +EDGE3 271 321 5.31425 0.00983701 -3.34013 0.00403641 0.00113441 -0.00319915 +EDGE3 270 321 4.97671 6.9835 -3.39554 -0.00345172 -0.00178737 0.121862 +EDGE3 271 320 4.77729 -6.97 -3.2671 0.00426974 0.0089309 -0.126248 +EDGE3 272 322 5.3127 -0.00047001 -3.35381 0.0100724 -0.0064886 0.00970991 +EDGE3 271 322 4.99153 7.00617 -3.41097 0.00148069 0.00345704 0.131892 +EDGE3 272 321 4.77213 -6.99046 -3.29368 -0.00147294 -0.00227328 -0.130607 +EDGE3 273 323 5.31904 -0.00866203 -3.33558 0.00768825 -0.00444776 0.00805644 +EDGE3 272 323 4.96925 7.01963 -3.41329 0.00907159 0.00331943 0.127475 +EDGE3 273 322 4.77239 -7.0253 -3.28563 0.0107447 0.000875417 -0.121445 +EDGE3 274 324 5.30576 0.00528195 -3.34099 0.00686695 -0.000954944 -0.00376616 +EDGE3 273 324 4.98007 7.01751 -3.44573 -0.000240119 0.00203245 0.121152 +EDGE3 274 323 4.76368 -7.02255 -3.27398 0.00605046 0.000954305 -0.129642 +EDGE3 275 325 5.30366 -0.000733496 -3.37514 0.00684711 -0.00177394 0.000724025 +EDGE3 274 325 4.95174 7.05491 -3.43747 0.00531212 -0.00114522 0.130808 +EDGE3 275 324 4.75829 -7.03927 -3.30075 0.00167727 0.00757102 -0.126605 +EDGE3 276 326 5.29701 -0.00884783 -3.36267 9.63852e-05 0.0055247 -0.00230038 +EDGE3 275 326 4.96677 7.06858 -3.44353 0.000538449 0.0106302 0.11951 +EDGE3 276 325 4.75673 -7.02554 -3.29616 -0.00263592 -0.000361563 -0.131996 +EDGE3 277 327 5.30923 -0.000414631 -3.38874 -0.00342415 -0.00814345 0.00680564 +EDGE3 276 327 4.95408 7.07626 -3.4497 0.00422264 0.00256547 0.129127 +EDGE3 277 326 4.73723 -7.06489 -3.32266 -0.00344716 0.000691333 -0.128637 +EDGE3 278 328 5.31552 0.00362209 -3.38106 -0.00247284 0.00803886 -0.00614412 +EDGE3 277 328 4.95582 7.0906 -3.44805 -0.00111338 0.000577849 0.127826 +EDGE3 278 327 4.73156 -7.0878 -3.32598 -0.00370094 0.00122652 -0.128847 +EDGE3 279 329 5.27515 -0.0101051 -3.38517 0.00456258 0.00275102 0.00484745 +EDGE3 278 329 4.95016 7.09391 -3.45135 0.000443529 -0.00295582 0.120287 +EDGE3 279 328 4.75325 -7.07823 -3.32672 0.00271708 6.75249e-05 -0.12499 +EDGE3 280 330 5.28396 0.00321603 -3.40262 0.00603177 -0.00385507 0.00118044 +EDGE3 279 330 4.93358 7.12576 -3.46284 -0.00296045 0.00227558 0.127415 +EDGE3 280 329 4.73094 -7.09562 -3.32803 -0.00523736 -0.00433921 -0.125377 +EDGE3 281 331 5.26972 0.0224014 -3.38718 -0.00632536 0.00159225 0.0024423 +EDGE3 280 331 4.93153 7.13552 -3.466 0.00432328 0.00310229 0.124446 +EDGE3 281 330 4.72143 -7.07438 -3.33263 0.00117903 -0.00404315 -0.130857 +EDGE3 282 332 5.27076 0.00222047 -3.42029 -0.0043592 -0.00346917 0.00700112 +EDGE3 281 332 4.9296 7.13237 -3.48967 -0.00674608 -0.00571493 0.131041 +EDGE3 282 331 4.73063 -7.11675 -3.34812 0.00387357 0.00715841 -0.13926 +EDGE3 283 333 5.26606 0.00316672 -3.42244 -0.00394095 0.00125985 0.00608847 +EDGE3 283 332 4.70984 -7.14131 -3.34317 -0.00128959 -0.0068415 -0.129993 +EDGE3 282 333 4.93218 7.1529 -3.48956 0.00834592 -0.00425056 0.123028 +EDGE3 283 334 4.91817 7.1598 -3.5008 -0.00260229 -0.00267104 0.124957 +EDGE3 284 334 5.25345 0.0101857 -3.41853 0.00300856 -0.00401419 -0.00300591 +EDGE3 285 335 5.25458 -0.00694611 -3.42936 -0.00145348 0.0086461 0.00508639 +EDGE3 284 333 4.71603 -7.14881 -3.35085 0.00087731 0.00200956 -0.135854 +EDGE3 285 334 4.70884 -7.16362 -3.35226 0.00475534 0.00309204 -0.125194 +EDGE3 284 335 4.92487 7.17077 -3.49546 0.00303139 0.00661435 0.115379 +EDGE3 285 336 4.91872 7.17326 -3.50102 0.00539882 0.00256458 0.12944 +EDGE3 286 336 5.27306 0.0131506 -3.42832 -0.00683929 0.00300978 0.0051484 +EDGE3 286 335 4.71324 -7.16693 -3.3728 0.00367022 -0.0125966 -0.130253 +EDGE3 287 337 5.27263 -0.0219927 -3.43973 -0.000109206 -0.00331181 0.005187 +EDGE3 287 336 4.69797 -7.19129 -3.37384 0.00686909 -0.0101516 -0.122963 +EDGE3 286 337 4.91255 7.19295 -3.49994 0.00235877 0.00271487 0.130435 +EDGE3 287 338 4.89709 7.22271 -3.51303 0.0088595 -4.56621e-05 0.126314 +EDGE3 288 338 5.23937 -0.00513111 -3.44776 0.00314584 -0.00526636 0.0077139 +EDGE3 289 339 5.23563 -0.0143446 -3.4617 -0.00989623 -0.000472679 0.00677214 +EDGE3 288 337 4.68468 -7.19317 -3.3767 -0.00106196 -0.00318699 -0.13387 +EDGE3 289 338 4.675 -7.21426 -3.39375 0.000997063 -0.00636891 -0.121707 +EDGE3 288 339 4.90814 7.22878 -3.52055 -0.000913168 -0.000920795 0.115553 +EDGE3 289 340 4.88888 7.2394 -3.52267 -0.0028627 -0.00570697 0.122994 +EDGE3 290 340 5.2295 0.00188221 -3.46116 -0.00434062 0.00202252 0.000374372 +EDGE3 291 341 5.22297 0.00112411 -3.46572 0.00183029 -0.00576059 0.00788 +EDGE3 290 339 4.6815 -7.23937 -3.40209 0.00208773 -0.00533075 -0.130698 +EDGE3 291 340 4.67689 -7.24437 -3.39699 0.000525311 0.00209842 -0.125583 +EDGE3 290 341 4.87221 7.25773 -3.53869 -0.000673119 -0.00123875 0.121079 +EDGE3 291 342 4.89265 7.25651 -3.53389 0.0094974 0.0111056 0.122576 +EDGE3 292 342 5.23107 0.0036855 -3.48859 0.00433732 -0.000527689 -0.00370109 +EDGE3 292 341 4.67478 -7.2437 -3.40606 -0.00393988 0.0017299 -0.120952 +EDGE3 293 343 5.23099 -0.00281096 -3.46143 0.00494847 0.0022926 -0.00311287 +EDGE3 293 342 4.6472 -7.26485 -3.41132 0.00623181 0.00533696 -0.120062 +EDGE3 292 343 4.8593 7.26975 -3.55761 -0.00131468 0.00235821 0.130712 +EDGE3 294 344 5.21395 -6.03386e-05 -3.50948 0.00541413 -0.00300986 -0.00364755 +EDGE3 293 344 4.87142 7.28286 -3.57095 -0.00427414 0.00410075 0.121784 +EDGE3 294 343 4.65879 -7.25234 -3.41387 -0.00353217 0.00435463 -0.123299 +EDGE3 294 345 4.86422 7.31563 -3.55943 0.00393639 -0.00249 0.129747 +EDGE3 295 345 5.20824 0.0183396 -3.49286 -0.00421197 0.00709284 -0.00532277 +EDGE3 295 344 4.64913 -7.28184 -3.44068 0.0014658 0.00597931 -0.122072 +EDGE3 296 346 5.21647 -0.00822866 -3.52919 -0.00324745 0.0057251 -0.000538479 +EDGE3 295 346 4.8818 7.30648 -3.56118 0.000422618 0.0022513 0.122864 +EDGE3 296 345 4.6505 -7.30003 -3.4258 -0.00637986 -0.00134523 -0.124619 +EDGE3 297 347 5.2015 0.0198264 -3.52329 0.00117392 -0.00124138 -0.00589716 +EDGE3 297 346 4.63027 -7.31738 -3.44967 -0.00118144 -0.0060611 -0.116847 +EDGE3 296 347 4.85705 7.32633 -3.59102 -0.00329295 0.00526941 0.125969 +EDGE3 298 348 5.20122 -0.00702076 -3.51647 -0.00153437 -0.00315206 -0.0056583 +EDGE3 297 348 4.85261 7.3676 -3.59127 0.00440251 0.00134394 0.113785 +EDGE3 298 347 4.62493 -7.33831 -3.45149 0.00862939 -0.00448048 -0.11856 +EDGE3 298 349 4.86003 7.36735 -3.60227 0.00412265 0.00291451 0.118019 +EDGE3 299 349 5.19349 0.00158059 -3.50666 0.00281171 0.00503243 0.00154164 +EDGE3 300 350 5.20798 -0.00618375 -3.53289 0.00760205 0.000930222 -0.00237812 +EDGE3 299 348 4.63105 -7.32634 -3.45171 -0.00145691 0.00110253 -0.124696 +EDGE3 299 350 4.82996 7.36763 -3.60765 0.00406258 0.00412285 0.121856 +EDGE3 300 349 4.63802 -7.35895 -3.46214 -0.0105528 0.00261566 -0.122303 +EDGE3 300 351 4.8221 7.38695 -3.61685 -0.00522341 0.0023905 0.126793 +EDGE3 301 351 5.18521 -0.0198223 -3.53 -0.00786829 -0.00756402 0.00681044 +EDGE3 301 350 4.63089 -7.35775 -3.4667 0.0013421 -0.0100733 -0.124341 +EDGE3 302 352 5.18826 0.00197664 -3.5428 0.00231724 0.00163158 0.00394299 +EDGE3 302 351 4.6086 -7.37857 -3.46896 -0.00516796 0.00622784 -0.122651 +EDGE3 301 352 4.83067 7.40378 -3.61332 -0.00332967 -0.00174264 0.12348 +EDGE3 303 353 5.19223 -0.0183207 -3.56474 -0.000138575 -0.000629148 -0.00617778 +EDGE3 302 353 4.82893 7.40769 -3.62899 0.000648136 0.00612907 0.120924 +EDGE3 303 352 4.61915 -7.38958 -3.49484 0.00529113 0.00154781 -0.125388 +EDGE3 303 354 4.81161 7.40616 -3.62146 0.0064561 -0.00123142 0.123501 +EDGE3 304 354 5.1802 -0.0016878 -3.5434 -0.000133045 -0.00169137 0.000416754 +EDGE3 305 355 5.17575 0.00933508 -3.55473 -0.00808288 0.0117736 -0.00031732 +EDGE3 304 353 4.61143 -7.39372 -3.47867 -0.00779878 0.0105422 -0.128794 +EDGE3 305 354 4.60188 -7.43271 -3.50745 -0.00130728 -0.00120823 -0.129831 +EDGE3 304 355 4.81899 7.43288 -3.64818 -0.00919267 -0.00147422 0.123198 +EDGE3 306 356 5.16891 -0.000348674 -3.5783 -0.00444664 -0.0048138 -0.00303024 +EDGE3 305 356 4.78846 7.43657 -3.61986 0.00128933 0.00382521 0.119512 +EDGE3 306 355 4.61475 -7.44814 -3.49232 0.00226921 0.00401331 -0.117983 +EDGE3 306 357 4.80174 7.48053 -3.64725 0.00413559 0.00526274 0.13057 +EDGE3 307 357 5.15888 0.00168566 -3.57661 0.00335223 -0.0103393 -0.00192021 +EDGE3 307 356 4.61197 -7.4424 -3.50066 -0.00696626 0.0038236 -0.120756 +EDGE3 308 358 5.15732 -0.00170081 -3.58842 0.000777634 -0.00188635 -0.00492502 +EDGE3 307 358 4.79288 7.4481 -3.65137 0.0109289 0.00286741 0.125838 +EDGE3 308 357 4.5874 -7.46866 -3.49513 -0.0124088 0.00239726 -0.133055 +EDGE3 309 359 5.16267 -0.011913 -3.6099 -0.0052221 -0.00123747 -0.00558877 +EDGE3 309 358 4.58534 -7.46716 -3.51699 0.000661772 -0.00527076 -0.123893 +EDGE3 308 359 4.77646 7.49874 -3.65473 0.00375709 -0.00212942 0.123314 +EDGE3 310 360 5.15613 -0.00676186 -3.58818 0.00515092 -0.00168444 -0.00230858 +EDGE3 309 360 4.77329 7.49046 -3.66944 0.00300008 -0.00448722 0.124629 +EDGE3 310 359 4.5854 -7.46714 -3.50692 -0.00114439 -0.00262357 -0.120497 +EDGE3 310 361 4.77054 7.49984 -3.66051 0.00598418 0.00651171 0.125241 +EDGE3 311 361 5.1554 0.00169213 -3.59582 0.000390798 -0.00571874 -0.00723143 +EDGE3 312 362 5.13489 0.0109115 -3.60482 -0.00613456 -0.00377641 -0.00355483 +EDGE3 311 360 4.57274 -7.5155 -3.50853 -0.00114815 0.00145272 -0.130297 +EDGE3 312 361 4.56995 -7.50106 -3.51624 -0.000264858 0.00442652 -0.12955 +EDGE3 311 362 4.76898 7.5123 -3.65724 -0.00152231 -0.00536298 0.131292 +EDGE3 312 363 4.77641 7.53275 -3.65812 0.00160941 0.00324989 0.12889 +EDGE3 313 363 5.14432 -0.00244244 -3.61247 0.00762064 0.00675734 -0.00369396 +EDGE3 313 362 4.56284 -7.51367 -3.5286 -0.0045661 -0.00138884 -0.126264 +EDGE3 314 364 5.11153 -0.00158307 -3.61078 -0.000804189 -0.00208261 -0.00748232 +EDGE3 313 364 4.76757 7.54431 -3.68145 -0.00142991 0.00433295 0.12435 +EDGE3 315 365 5.11869 -0.00293335 -3.62299 -0.00426283 -0.0023868 0.00139749 +EDGE3 314 363 4.56319 -7.54313 -3.55927 0.00343744 -0.0033267 -0.13163 +EDGE3 315 364 4.54847 -7.5318 -3.54709 -0.00687866 -0.00132723 -0.120884 +EDGE3 314 365 4.75019 7.56652 -3.6987 0.00951762 0.00207759 0.12031 +EDGE3 315 366 4.7441 7.56844 -3.7084 0.00518891 0.00751403 0.126363 +EDGE3 316 366 5.1099 0.0109213 -3.63342 0.00115441 -0.0029587 -0.00518759 +EDGE3 316 365 4.55987 -7.56201 -3.5702 0.000310677 0.0013978 -0.125583 +EDGE3 317 367 5.13464 0.00281821 -3.61914 0.00479334 -0.000981886 -0.00758962 +EDGE3 316 367 4.7511 7.59105 -3.71473 0.00490971 -0.00033883 0.129078 +EDGE3 318 368 5.11945 0.000757482 -3.66104 -0.00224391 -0.00302172 -0.00508161 +EDGE3 317 366 4.55466 -7.55802 -3.55487 0.00660199 -0.00520606 -0.125313 +EDGE3 318 367 4.54488 -7.58847 -3.57734 -0.00258183 0.0046155 -0.12355 +EDGE3 317 368 4.7499 7.60446 -3.7167 0.00131168 0.00128628 0.130647 +EDGE3 319 369 5.10886 -0.00994389 -3.65762 0.000441408 -0.00623437 -0.0017055 +EDGE3 318 369 4.7442 7.60388 -3.72096 -0.000989965 0.00647954 0.130643 +EDGE3 319 368 4.53896 -7.57344 -3.59383 -0.00600196 0.00251413 -0.121998 +EDGE3 320 370 5.11717 -0.00719236 -3.6749 -0.0013097 -0.00755472 0.00731651 +EDGE3 319 370 4.73118 7.62864 -3.73163 0.00168694 -0.00121312 0.122794 +EDGE3 320 369 4.52363 -7.59098 -3.58188 0.00715951 -0.00384393 -0.125575 +EDGE3 321 371 5.11018 0.00659597 -3.66973 -0.0029433 0.00131195 0.00413438 +EDGE3 320 371 4.70403 7.64376 -3.74083 0.00328758 -0.000922663 0.118704 +EDGE3 321 370 4.5232 -7.61178 -3.59258 -0.000152425 0.00187952 -0.126411 +EDGE3 322 372 5.1004 0.00673136 -3.67494 -0.000491537 0.00470768 -0.00222359 +EDGE3 321 372 4.71606 7.65125 -3.76729 -0.00550151 0.00185853 0.125216 +EDGE3 322 371 4.50665 -7.62888 -3.57787 0.00178917 0.00682545 -0.128463 +EDGE3 323 373 5.104 0.0104661 -3.67376 0.00656823 0.00301126 -0.00264311 +EDGE3 322 373 4.70883 7.6548 -3.73591 -0.00283797 0.00826127 0.129503 +EDGE3 323 372 4.52899 -7.64943 -3.59538 -0.00525952 0.00108687 -0.123604 +EDGE3 324 374 5.06849 -0.00541623 -3.69268 0.00855555 0.0106644 0.00473618 +EDGE3 323 374 4.71393 7.66471 -3.77234 -0.00247908 0.00178324 0.125719 +EDGE3 324 373 4.50719 -7.65011 -3.61784 -0.00701898 0.00447824 -0.120935 +EDGE3 325 375 5.07964 -0.0123011 -3.68635 -0.000432729 -0.00488317 -0.00523085 +EDGE3 324 375 4.71832 7.66912 -3.78193 -0.000533478 0.00377659 0.124391 +EDGE3 325 374 4.49059 -7.68733 -3.60857 -0.00207099 -0.0023721 -0.120907 +EDGE3 326 376 5.06142 0.00857789 -3.69571 0.00505374 -0.00404372 -0.00654221 +EDGE3 325 376 4.69887 7.69094 -3.77465 -0.0113286 0.000878981 0.124581 +EDGE3 326 375 4.4938 -7.6671 -3.61888 0.00249322 -0.00636655 -0.129164 +EDGE3 327 377 5.06841 -0.00128512 -3.69641 0.00844676 -0.00174208 -0.000794641 +EDGE3 326 377 4.70374 7.71111 -3.76744 0.00452571 0.00461192 0.126306 +EDGE3 327 376 4.48832 -7.69642 -3.6208 -0.00115376 -0.00461354 -0.118722 +EDGE3 328 378 5.07642 -0.0124288 -3.72591 0.00393803 -0.00697853 -0.00174498 +EDGE3 327 378 4.65454 7.71284 -3.7749 -0.000307572 -0.0092107 0.133214 +EDGE3 328 377 4.46614 -7.7034 -3.62058 -0.00772183 -0.00759098 -0.122143 +EDGE3 329 379 5.06823 0.00254853 -3.73311 0.00926039 0.00586166 0.00293346 +EDGE3 328 379 4.68742 7.75239 -3.77732 -0.0128152 0.00143088 0.132932 +EDGE3 329 378 4.47478 -7.70583 -3.61802 -0.00276804 0.00675404 -0.11492 +EDGE3 330 380 5.08048 0.0104838 -3.73695 -0.000258345 -0.00479206 0.000565091 +EDGE3 329 380 4.67565 7.74221 -3.79901 -0.00457615 0.00234753 0.120683 +EDGE3 330 379 4.46535 -7.74197 -3.64818 -0.000738568 -0.00684931 -0.126316 +EDGE3 331 381 5.06273 0.00473243 -3.72695 -0.0099737 -0.00188187 -0.000940728 +EDGE3 330 381 4.66762 7.7573 -3.79597 0.00562467 -0.00756877 0.126954 +EDGE3 331 380 4.46236 -7.74217 -3.65984 0.00469702 0.00448384 -0.125584 +EDGE3 332 382 5.03988 -0.00474901 -3.74532 -0.00262537 -0.00132171 -0.00230994 +EDGE3 331 382 4.66118 7.76664 -3.80789 0.00924951 -0.0039651 0.126674 +EDGE3 332 381 4.46249 -7.75677 -3.65522 0.00187573 0.00275606 -0.131749 +EDGE3 333 383 5.03589 0.0175517 -3.7563 0.00485334 0.000462331 0.000245739 +EDGE3 332 383 4.64077 7.78382 -3.81455 0.00504277 0.00204101 0.134913 +EDGE3 333 382 4.44585 -7.77146 -3.68641 0.000925746 0.00792186 -0.131931 +EDGE3 334 384 5.03527 -0.0018251 -3.75224 0.00331544 -0.00228455 0.000625089 +EDGE3 333 384 4.66634 7.80395 -3.82592 -0.0116588 -0.00200891 0.118595 +EDGE3 334 383 4.45522 -7.78469 -3.67846 -0.00544015 -0.000445811 -0.13155 +EDGE3 335 385 5.02008 -0.00546497 -3.76129 8.87587e-05 -0.00920985 0.00559895 +EDGE3 334 385 4.65739 7.80763 -3.85247 0.00203164 -0.00769545 0.135167 +EDGE3 335 384 4.45397 -7.7687 -3.67883 -0.000937056 -0.0014124 -0.129615 +EDGE3 336 386 5.03023 0.0112397 -3.77542 -0.0103919 0.00356547 0.000823122 +EDGE3 335 386 4.64327 7.81319 -3.85476 0.000655539 0.0083018 0.131288 +EDGE3 336 385 4.43866 -7.80083 -3.69008 0.00238642 -0.00809175 -0.125833 +EDGE3 337 387 5.02415 0.0111479 -3.76232 -0.0045081 -0.00187194 0.0070478 +EDGE3 336 387 4.64037 7.8315 -3.84794 -0.00539877 -0.00396664 0.124774 +EDGE3 337 386 4.43058 -7.81326 -3.69106 -0.00395819 0.0026372 -0.117537 +EDGE3 338 388 5.02551 -0.00177614 -3.76476 0.00683327 -0.00564778 -0.00898816 +EDGE3 337 388 4.64839 7.83148 -3.84044 -0.00462735 -0.0085297 0.124985 +EDGE3 338 387 4.42797 -7.84025 -3.68615 0.00789601 -0.00237466 -0.117125 +EDGE3 339 389 5.02837 -0.0130423 -3.78011 -0.00132524 0.00459681 0.0047369 +EDGE3 338 389 4.62712 7.83479 -3.84777 -0.000344857 0.00709117 0.129234 +EDGE3 339 388 4.41725 -7.83962 -3.69963 0.00257468 -0.00796599 -0.123356 +EDGE3 340 390 5.00666 0.0015451 -3.7959 0.0058095 0.00943503 -0.00229497 +EDGE3 339 390 4.62899 7.86684 -3.85957 -0.00177122 -0.00242763 0.136042 +EDGE3 340 389 4.41756 -7.8542 -3.70838 0.000854946 -0.00036804 -0.120285 +EDGE3 341 391 5.01263 -0.00450694 -3.80809 -0.000265533 0.0100209 -0.00742185 +EDGE3 340 391 4.61307 7.88668 -3.85863 0.00254935 -0.00605278 0.119872 +EDGE3 341 390 4.41345 -7.87187 -3.73619 -0.00983164 0.000274363 -0.126221 +EDGE3 342 392 4.99801 -0.00661182 -3.80441 -0.00193643 0.000863579 0.00621028 +EDGE3 341 392 4.61436 7.89708 -3.86513 -0.00068812 0.00711011 0.138367 +EDGE3 342 391 4.41156 -7.87705 -3.74114 0.000972471 -0.00398341 -0.129168 +EDGE3 343 393 4.99443 -0.0134479 -3.82299 -0.00529948 -0.00266649 0.00525289 +EDGE3 342 393 4.60678 7.8869 -3.87608 -0.00239984 -0.00234137 0.122291 +EDGE3 343 392 4.4027 -7.88152 -3.71704 0.00339445 -0.00297566 -0.116958 +EDGE3 344 394 4.99036 0.0038501 -3.82268 0.000449781 -0.00771565 0.00215886 +EDGE3 343 394 4.59127 7.925 -3.88018 0.00268071 0.00913486 0.130336 +EDGE3 344 393 4.40116 -7.90468 -3.74116 0.0121208 -0.00661542 -0.116291 +EDGE3 345 395 4.9769 0.0165764 -3.8301 0.000390736 0.000869437 0.00486579 +EDGE3 344 395 4.60265 7.91649 -3.89904 0.00307459 0.00404805 0.127409 +EDGE3 345 394 4.39139 -7.90923 -3.73106 -0.000897178 -0.00378701 -0.121292 +EDGE3 346 396 4.98362 -0.0226614 -3.82845 -0.00277821 0.00219071 -0.00276573 +EDGE3 345 396 4.57571 7.94452 -3.88035 -0.00261042 -0.00487108 0.12797 +EDGE3 346 395 4.36995 -7.94154 -3.73081 -0.00148922 -0.00807076 -0.123094 +EDGE3 347 397 4.97392 0.0104379 -3.83003 -0.00904234 -0.0031929 0.000792214 +EDGE3 346 397 4.59403 7.95425 -3.91384 -0.00609907 0.00466886 0.128546 +EDGE3 347 396 4.36967 -7.93159 -3.76081 0.00131358 0.00171544 -0.115889 +EDGE3 348 398 4.96127 -0.0174523 -3.84232 -0.00191327 -0.000499655 0.00405152 +EDGE3 347 398 4.58851 7.96818 -3.91725 -0.00194372 -0.00183641 0.120014 +EDGE3 348 397 4.37238 -7.95723 -3.74827 -0.00771918 -0.00845821 -0.119941 +EDGE3 349 399 4.97217 0.00263291 -3.82564 -0.00115816 0.000622225 -0.000931302 +EDGE3 348 399 4.5709 7.97975 -3.91574 -0.00314144 -0.00029531 0.130894 +EDGE3 349 398 4.36857 -7.94575 -3.76298 -0.00169906 0.00262548 -0.125164 +EDGE3 350 400 4.97158 0.00796588 -3.85914 0.0153152 -0.00756615 0.00154984 +EDGE3 349 400 4.56331 7.98318 -3.92962 0.00296887 -0.00069307 0.11805 +EDGE3 350 399 4.36876 -7.95946 -3.7666 0.00346655 -0.0126685 -0.125872 +EDGE3 351 401 4.95679 0.0196543 -3.86608 0.00333032 0.00496832 -0.0018899 +EDGE3 350 401 4.54953 8.00478 -3.93261 0.00633296 -0.0056816 0.115595 +EDGE3 351 400 4.35709 -7.97257 -3.78395 -0.00893347 -0.00550349 -0.128877 +EDGE3 352 402 4.9479 0.0202718 -3.87565 0.0042 0.0109065 0.00750408 +EDGE3 351 402 4.54827 8.02094 -3.93395 0.00543631 -0.00238215 0.11983 +EDGE3 352 401 4.3509 -8.00137 -3.79433 0.000258262 0.00248269 -0.126069 +EDGE3 353 403 4.97094 0.00656891 -3.88351 0.000967876 -0.00191513 -0.000823 +EDGE3 352 403 4.54606 8.01971 -3.92846 0.00370851 -0.0042957 0.115558 +EDGE3 353 402 4.36032 -8.0005 -3.79494 -0.00101843 -1.45854e-05 -0.12755 +EDGE3 354 404 4.94321 0.000866796 -3.85967 -0.00231341 -0.00507498 -0.00325392 +EDGE3 353 404 4.53802 8.034 -3.9549 -0.00870796 0.000309774 0.122371 +EDGE3 354 403 4.3427 -8.03834 -3.80889 0.00180847 -0.00595298 -0.117025 +EDGE3 355 405 4.9601 0.00668282 -3.87911 -0.00188927 0.00897153 -0.0014764 +EDGE3 354 405 4.53679 8.06909 -3.9625 0.000904624 0.00104172 0.128238 +EDGE3 355 404 4.33386 -8.0327 -3.79066 -0.00141185 0.00650725 -0.129932 +EDGE3 356 406 4.92512 -0.0140995 -3.90582 -0.00163314 -0.00336223 0.000725895 +EDGE3 355 406 4.50891 8.06352 -3.96353 0.00678225 0.00113704 0.132028 +EDGE3 356 405 4.34827 -8.05724 -3.80597 -0.00164758 0.00107093 -0.133234 +EDGE3 357 407 4.92834 0.00401079 -3.88636 -0.0057786 -0.00520713 -0.00609876 +EDGE3 356 407 4.51622 8.0763 -3.97294 0.000985639 -0.00062198 0.124648 +EDGE3 357 406 4.33071 -8.04641 -3.80706 -0.00181967 0.00852725 -0.126467 +EDGE3 358 408 4.92374 -0.00769128 -3.88007 -0.000246349 0.00397473 0.00406293 +EDGE3 357 408 4.51429 8.08558 -3.96669 0.0104701 -0.00635154 0.121852 +EDGE3 358 407 4.32092 -8.0872 -3.81755 0.000578147 0.00177707 -0.118891 +EDGE3 359 409 4.91243 -4.48047e-05 -3.92197 0.00110176 -0.017488 -0.00436426 +EDGE3 358 409 4.50767 8.09643 -3.98984 0.00275837 0.001117 0.118379 +EDGE3 359 408 4.30818 -8.09239 -3.83868 0.00248047 0.00109342 -0.128038 +EDGE3 360 410 4.91769 -0.00862005 -3.90588 0.0098829 -0.00917511 -3.45582e-05 +EDGE3 360 409 4.3116 -8.08913 -3.83987 -0.000605062 0.00399345 -0.125637 +EDGE3 359 410 4.51167 8.10622 -3.98202 0.0102244 0.000125645 0.132624 +EDGE3 361 411 4.92753 0.00138583 -3.90261 0.00566904 -0.0105127 -0.00829726 +EDGE3 360 411 4.5026 8.11997 -4.02051 0.00107883 -0.000397466 0.126768 +EDGE3 361 410 4.31829 -8.11356 -3.83646 0.000546509 0.00167291 -0.13124 +EDGE3 362 412 4.9018 0.00469098 -3.92868 -0.00238059 0.00257935 -0.00256316 +EDGE3 361 412 4.48872 8.13108 -3.98362 -6.03082e-05 0.000195551 0.127383 +EDGE3 362 411 4.2927 -8.12065 -3.84489 0.00444567 0.00367119 -0.130845 +EDGE3 363 413 4.90601 -0.0130183 -3.91941 0.00405986 -0.00573173 -0.000792147 +EDGE3 362 413 4.48718 8.13628 -4.00359 0.00392991 -0.00495398 0.124901 +EDGE3 363 412 4.29444 -8.12482 -3.83232 0.00418876 0.00262949 -0.127627 +EDGE3 364 414 4.90288 0.00682515 -3.9566 -0.00931283 0.00240036 0.00240636 +EDGE3 363 414 4.47365 8.17333 -3.9964 -0.00339396 -0.00545757 0.122761 +EDGE3 364 413 4.28793 -8.14775 -3.86161 0.00546352 0.00223075 -0.123646 +EDGE3 365 415 4.88162 0.0031664 -3.95582 0.00143412 -0.0122659 0.000864707 +EDGE3 364 415 4.48278 8.16897 -4.01549 -0.000367708 0.00505097 0.123902 +EDGE3 365 414 4.28961 -8.14301 -3.8486 0.00427035 0.00755624 -0.134858 +EDGE3 366 416 4.88913 -0.00445064 -3.9426 0.000201074 -0.0104031 -0.00317898 +EDGE3 365 416 4.4744 8.18015 -4.01416 -0.00338068 0.00570549 0.121576 +EDGE3 366 415 4.26577 -8.18359 -3.84894 0.00196663 0.00280892 -0.127453 +EDGE3 367 417 4.88763 0.0117824 -3.94096 -0.0111957 0.00419083 -0.00402932 +EDGE3 366 417 4.44246 8.1927 -4.05719 -0.00111178 -0.00557221 0.12038 +EDGE3 367 416 4.25741 -8.17834 -3.8867 -0.00471152 -0.00300538 -0.122852 +EDGE3 368 418 4.8672 -0.00332876 -3.95407 0.00301769 -0.00333804 -0.00276251 +EDGE3 367 418 4.46188 8.1934 -4.03065 -0.00841869 -0.00153824 0.133318 +EDGE3 368 417 4.28211 -8.18649 -3.87103 -0.00135249 -0.0075627 -0.117761 +EDGE3 369 419 4.86777 0.0168232 -3.96217 0.0104887 -0.000737349 0.002571 +EDGE3 368 419 4.43269 8.20725 -4.03893 0.00510678 0.00130811 0.128755 +EDGE3 369 418 4.2549 -8.20326 -3.89327 -0.00487672 -0.00715176 -0.1219 +EDGE3 370 420 4.85165 -0.00361041 -3.96909 -0.000445213 -0.0016333 0.00974149 +EDGE3 369 420 4.45416 8.21632 -4.04396 -0.00672489 0.00328322 0.129418 +EDGE3 370 419 4.26593 -8.23024 -3.8918 -0.000447123 -0.00335364 -0.122771 +EDGE3 371 421 4.85396 0.00512663 -3.97378 0.000242258 0.00321163 -0.00628078 +EDGE3 370 421 4.44817 8.24007 -4.05969 -0.00482967 -0.000564085 0.121999 +EDGE3 371 420 4.25196 -8.23152 -3.90844 0.00197604 0.00222262 -0.129877 +EDGE3 372 422 4.88366 0.00687048 -3.98764 -0.000733838 -9.00018e-05 0.000918687 +EDGE3 371 422 4.431 8.24759 -4.08428 0.012643 0.00745917 0.114915 +EDGE3 372 421 4.23055 -8.26477 -3.89364 0.000840027 0.0079207 -0.127134 +EDGE3 372 423 4.42686 8.28009 -4.08291 0.00291527 -0.00275457 0.122615 +EDGE3 373 423 4.83422 -0.0145329 -3.99674 0.00186163 -0.00181514 -0.00297329 +EDGE3 374 424 4.83735 -0.0194247 -3.99913 -0.0054322 -0.0021102 0.00791248 +EDGE3 373 422 4.22027 -8.26965 -3.90999 0.00218752 -0.0111067 -0.115003 +EDGE3 374 423 4.23382 -8.26719 -3.91157 0.00199242 0.00313487 -0.128609 +EDGE3 373 424 4.42313 8.26656 -4.08339 -0.0019238 -0.00370224 0.129955 +EDGE3 374 425 4.40896 8.28436 -4.08278 -0.00249355 -0.000405683 0.129348 +EDGE3 375 425 4.82304 -0.0116702 -4.01642 -0.00296505 0.00690399 0.00355008 +EDGE3 376 426 4.84161 0.0170846 -4.01126 0.00135222 0.00185468 -0.00285597 +EDGE3 375 424 4.22773 -8.26426 -3.928 0.000186728 -3.32109e-05 -0.125906 +EDGE3 376 425 4.21552 -8.27546 -3.93386 0.00341439 -0.00299966 -0.122665 +EDGE3 375 426 4.4097 8.30817 -4.07504 0.00536028 0.00205262 0.125994 +EDGE3 376 427 4.4012 8.29609 -4.09623 0.00506341 0.00368494 0.131624 +EDGE3 377 427 4.8216 8.72762e-05 -4.01393 0.0110272 1.18326e-05 -0.00726676 +EDGE3 377 426 4.217 -8.31094 -3.92639 -0.0012704 -0.00522473 -0.125477 +EDGE3 378 428 4.83096 0.00665987 -4.0066 0.00802441 0.00340213 0.00220694 +EDGE3 378 427 4.21255 -8.3289 -3.9336 -0.00171791 0.00247462 -0.131841 +EDGE3 377 428 4.39072 8.33862 -4.1012 -0.00405505 -0.0109167 0.131917 +EDGE3 378 429 4.40049 8.33277 -4.10021 -0.00548825 -0.00612841 0.122503 +EDGE3 379 429 4.82011 0.00292529 -4.01865 -0.00490138 0.0017629 -0.00244888 +EDGE3 380 430 4.82761 0.00687348 -4.03069 -0.00616107 0.000891643 0.00391855 +EDGE3 379 428 4.20428 -8.32005 -3.94715 -0.00215372 -0.00217059 -0.127539 +EDGE3 380 429 4.20317 -8.31536 -3.95238 -0.00447876 -0.00064154 -0.132706 +EDGE3 379 430 4.39352 8.33435 -4.11152 -0.00625486 0.00522705 0.129128 +EDGE3 381 431 4.80538 -0.00683138 -4.03787 -0.00278676 0.00684405 -0.00167718 +EDGE3 380 431 4.383 8.34591 -4.11771 0.00461078 -0.00378762 0.127935 +EDGE3 381 430 4.19461 -8.34465 -3.94652 0.00498655 -0.00266467 -0.123359 +EDGE3 381 432 4.37235 8.37976 -4.12615 -0.00430171 -0.00158883 0.121278 +EDGE3 382 432 4.81251 0.0142145 -4.05062 0.000738998 0.00284294 0.00088365 +EDGE3 383 433 4.79455 0.00189433 -4.05558 -0.00115964 0.000139413 -0.00105097 +EDGE3 382 431 4.19278 -8.35411 -3.95276 -0.0026177 0.00278343 -0.120264 +EDGE3 382 433 4.38938 8.39524 -4.12902 0.000949192 -0.00203818 0.123274 +EDGE3 383 432 4.18746 -8.35064 -3.95875 -0.00466211 -0.00151415 -0.122335 +EDGE3 383 434 4.37437 8.38866 -4.12978 0.00879626 -0.00108228 0.120529 +EDGE3 384 434 4.794 -0.00583219 -4.06493 0.000466625 0.00305896 0.00530155 +EDGE3 385 435 4.76924 0.0105372 -4.06437 -0.00134591 0.000327723 -0.00106986 +EDGE3 384 433 4.19986 -8.38454 -3.9545 0.00174562 0.0134921 -0.124859 +EDGE3 385 434 4.16821 -8.38969 -3.96196 0.00885095 0.0129451 -0.121571 +EDGE3 384 435 4.37063 8.39872 -4.14243 -0.00168188 0.00317365 0.13644 +EDGE3 385 436 4.34745 8.40599 -4.16178 -0.0050623 -0.0051752 0.131399 +EDGE3 386 436 4.79272 0.00695906 -4.07366 0.000298465 0.00909627 -0.0019957 +EDGE3 387 437 4.79155 0.00326566 -4.07639 -0.000159035 -0.00115927 -0.00231758 +EDGE3 386 435 4.17766 -8.38981 -3.97906 -0.00206209 0.00277342 -0.131217 +EDGE3 387 436 4.1733 -8.41433 -3.98587 -0.00201535 0.0111306 -0.124213 +EDGE3 386 437 4.33666 8.42184 -4.1611 0.00107242 0.00404979 0.125348 +EDGE3 388 438 4.7645 -0.00116036 -4.09109 -0.00316022 -0.000263544 -6.91563e-05 +EDGE3 387 438 4.34644 8.44141 -4.15977 0.00268993 -0.0120346 0.124085 +EDGE3 388 437 4.15408 -8.44965 -4.0065 -0.0032489 0.00802205 -0.13226 +EDGE3 389 439 4.76327 -0.00770417 -4.09312 -0.00787148 -0.00319326 -0.000474833 +EDGE3 388 439 4.34631 8.46564 -4.17703 -0.000616679 0.00577214 0.127916 +EDGE3 389 438 4.12336 -8.42825 -4.00604 -0.00549498 -0.00493104 -0.126304 +EDGE3 389 440 4.33144 8.46497 -4.18255 0.00830592 0.000627931 0.119467 +EDGE3 390 440 4.76206 0.00522355 -4.08442 -0.00237764 0.00117901 0.000296611 +EDGE3 391 441 4.76885 -0.0046574 -4.08039 0.000213674 0.0109031 -0.00543371 +EDGE3 390 439 4.1441 -8.46102 -4.01856 0.00703051 -0.00556671 -0.123222 +EDGE3 391 440 4.127 -8.46265 -4.01327 0.00206002 -0.00294082 -0.120706 +EDGE3 390 441 4.31041 8.46589 -4.16965 0.00713928 0.00239767 0.126659 +EDGE3 391 442 4.31409 8.48247 -4.21597 -0.00266734 0.0021525 0.120262 +EDGE3 392 442 4.75951 -0.0194552 -4.09559 -0.00320612 0.00205768 0.000807853 +EDGE3 393 443 4.75732 0.00137537 -4.12169 -0.00355339 -0.00154642 0.00187147 +EDGE3 392 441 4.11702 -8.45868 -4.01134 0.00011098 -0.00868365 -0.13826 +EDGE3 393 442 4.13345 -8.48151 -4.02344 -0.00217262 0.00322287 -0.134454 +EDGE3 392 443 4.30127 8.49153 -4.20789 0.0104067 0.000255658 0.129191 +EDGE3 393 444 4.30831 8.50131 -4.18799 -0.00390141 -0.00270911 0.118167 +EDGE3 394 444 4.72955 0.00869874 -4.12397 -0.00411443 -0.00406581 0.00602378 +EDGE3 395 445 4.71676 0.00657177 -4.13373 -0.00124225 0.00549297 -0.00904429 +EDGE3 394 443 4.10299 -8.51416 -4.02222 0.00248194 -0.00217062 -0.125143 +EDGE3 395 444 4.10536 -8.50181 -4.04599 -0.00174588 -0.00271071 -0.125821 +EDGE3 394 445 4.31005 8.52674 -4.21008 -0.00511435 0.00454499 0.129832 +EDGE3 395 446 4.29234 8.53121 -4.21907 -0.00429905 0.00317943 0.127785 +EDGE3 396 446 4.72033 -0.0019518 -4.12578 0.0012661 -0.00153326 -0.000449368 +EDGE3 397 447 4.74299 -0.00364977 -4.13202 -4.97661e-05 -0.00755684 -0.00526585 +EDGE3 396 445 4.09283 -8.53242 -4.05474 -0.00282266 -0.00201547 -0.129197 +EDGE3 396 447 4.28002 8.54441 -4.22462 -0.0036212 -0.0106854 0.123839 +EDGE3 397 446 4.11087 -8.52328 -4.05708 0.00238404 -0.00212055 -0.123346 +EDGE3 397 448 4.27282 8.53114 -4.20086 -0.00438108 -0.00727879 0.129392 +EDGE3 398 448 4.72746 0.00379485 -4.14278 0.00799445 0.0016098 0.00350092 +EDGE3 399 449 4.71728 -0.00230005 -4.13046 -0.00152274 -0.00332992 0.0118784 +EDGE3 398 447 4.07775 -8.5578 -4.04646 -0.00850334 0.00708971 -0.120855 +EDGE3 399 448 4.07602 -8.54279 -4.0715 -0.000824725 0.00455174 -0.130853 +EDGE3 398 449 4.28375 8.57912 -4.24273 0.00329938 0.00170942 0.13436 +EDGE3 399 450 4.27379 8.57434 -4.241 -0.00653824 -0.0037044 0.12218 +EDGE3 400 450 4.71202 -0.00458911 -4.15694 0.00207862 0.00194389 0.00849214 +EDGE3 400 449 4.07108 -8.57415 -4.05572 -0.00163788 0.0117923 -0.123832 +EDGE3 401 451 4.71027 -0.0010429 -4.14887 0.00114139 -0.000246267 0.000303934 +EDGE3 400 451 4.26122 8.58104 -4.24028 0.00416266 -0.00380019 0.125093 +EDGE3 402 452 4.70555 -0.000177511 -4.1709 0.00109319 -0.00875931 -0.00318283 +EDGE3 401 450 4.08889 -8.58432 -4.08811 0.00114032 0.00232697 -0.124844 +EDGE3 401 452 4.25175 8.60654 -4.24215 -0.00692016 0.000838846 0.120739 +EDGE3 402 451 4.07711 -8.58209 -4.08239 0.00667654 0.00078251 -0.127415 +EDGE3 402 453 4.23271 8.61763 -4.2623 0.0105967 -0.00230396 0.12052 +EDGE3 403 453 4.69742 0.0258518 -4.17836 -0.00291733 -0.00502013 -0.00486934 +EDGE3 403 452 4.06433 -8.59896 -4.07796 0.0124541 -0.00761885 -0.123026 +EDGE3 404 454 4.66896 0.00937462 -4.19122 -0.00262734 0.000766227 0.00505904 +EDGE3 404 453 4.0686 -8.59657 -4.09119 0.0100571 -0.00261986 -0.121255 +EDGE3 403 454 4.23947 8.62984 -4.23582 0.0119009 0.0063767 0.124468 +EDGE3 404 455 4.23251 8.63759 -4.26903 -0.00294338 -0.000752992 0.128835 +EDGE3 405 455 4.69048 -0.00521975 -4.1901 0.00749779 0.0076058 -0.00395745 +EDGE3 406 456 4.66284 -0.0144267 -4.19542 -0.000841928 -0.00232922 -0.00284939 +EDGE3 405 454 4.04716 -8.60464 -4.09334 -0.00701207 0.00303296 -0.128953 +EDGE3 406 455 4.03751 -8.64016 -4.10918 -0.00208913 0.00957555 -0.125272 +EDGE3 405 456 4.23753 8.64132 -4.28141 0.0107133 0.00188361 0.130507 +EDGE3 406 457 4.21455 8.65384 -4.2726 0.00820539 0.000338709 0.122027 +EDGE3 407 457 4.68114 -0.00184307 -4.18895 0.00179132 0.00166117 0.00753611 +EDGE3 407 456 4.02909 -8.63773 -4.11218 -0.0023262 -0.00470401 -0.133783 +EDGE3 408 458 4.67338 0.00692819 -4.21252 0.00540386 0.00232803 0.00415996 +EDGE3 407 458 4.21582 8.65786 -4.28609 0.00262166 0.00425399 0.127261 +EDGE3 408 457 4.04544 -8.67016 -4.12441 -0.00164382 -0.00832043 -0.123993 +EDGE3 409 459 4.65373 0.00246177 -4.20629 0.000858865 -0.00079496 0.00169577 +EDGE3 408 459 4.21147 8.68214 -4.30297 0.000708895 -0.00205957 0.128268 +EDGE3 409 458 4.03521 -8.67366 -4.10828 -0.00357964 0.000152626 -0.125052 +EDGE3 410 460 4.6427 -0.00140269 -4.21399 0.00173181 0.00143873 -0.00101598 +EDGE3 409 460 4.20046 8.66639 -4.29462 0.00368705 0.00718217 0.125177 +EDGE3 410 459 4.02075 -8.68485 -4.12672 -0.00354549 0.00203699 -0.126695 +EDGE3 411 461 4.66917 0.00404305 -4.22156 -0.00101616 -0.00373274 -0.00249198 +EDGE3 410 461 4.19997 8.68926 -4.3016 0.001801 0.00558589 0.125389 +EDGE3 411 460 4.01826 -8.6936 -4.13387 -0.00018138 -0.000477563 -0.128652 +EDGE3 412 462 4.67163 -0.00481572 -4.22165 0.000794155 0.00741723 -0.00206011 +EDGE3 411 462 4.19611 8.70717 -4.31673 -0.00190511 -0.000557274 0.129973 +EDGE3 412 461 4.01349 -8.69078 -4.10698 0.000352223 -0.00870805 -0.124596 +EDGE3 413 463 4.65257 -0.00870496 -4.22101 -0.00710989 -0.00138723 -0.00859486 +EDGE3 412 463 4.18433 8.71896 -4.31277 -0.00214546 -0.000906057 0.123712 +EDGE3 413 462 3.99644 -8.70935 -4.14466 -0.000362304 0.00329408 -0.126208 +EDGE3 414 464 4.62103 0.0241052 -4.23638 -0.00514254 0.00185119 -0.00494612 +EDGE3 413 464 4.20174 8.73939 -4.30553 0.00460808 -0.00277764 0.113643 +EDGE3 414 463 3.99419 -8.72407 -4.13879 -0.00209654 -0.0013959 -0.127191 +EDGE3 415 465 4.64274 -0.0140296 -4.24531 -0.0077619 0.00694975 0.00584839 +EDGE3 414 465 4.17639 8.73773 -4.33067 -0.00186635 0.00178009 0.123322 +EDGE3 415 464 3.98291 -8.73845 -4.15898 0.00619411 0.00151918 -0.122943 +EDGE3 416 466 4.6338 0.00803756 -4.24064 -0.000672492 0.00118131 -0.000640919 +EDGE3 415 466 4.16805 8.7726 -4.33179 -0.000197155 0.00162769 0.128839 +EDGE3 416 465 3.99299 -8.7519 -4.15252 -0.00934493 -0.0100476 -0.125441 +EDGE3 417 467 4.63787 -0.00113345 -4.26319 0.00029973 -0.00327688 0.00172955 +EDGE3 416 467 4.15843 8.76355 -4.34447 -0.000646187 -0.00151652 0.13017 +EDGE3 417 466 3.97104 -8.75208 -4.1617 0.00204109 0.00743808 -0.129446 +EDGE3 418 468 4.62089 0.0155916 -4.24707 -0.00808739 -0.00439673 -0.000899771 +EDGE3 417 468 4.15494 8.78568 -4.35093 0.00492428 0.00280689 0.122005 +EDGE3 418 467 3.96834 -8.77367 -4.17113 0.00516713 0.00589029 -0.124305 +EDGE3 419 469 4.60461 -0.0103161 -4.27045 -0.00408807 -0.00186651 0.00649129 +EDGE3 418 469 4.16138 8.79426 -4.34257 -0.00491058 0.00910918 0.117558 +EDGE3 419 468 3.95292 -8.77313 -4.16075 -0.00251864 0.00134444 -0.127788 +EDGE3 420 470 4.60279 0.0152601 -4.26772 -0.00263282 -0.000804701 0.00434388 +EDGE3 419 470 4.14438 8.79874 -4.35431 0.0147857 0.000957149 0.13373 +EDGE3 420 469 3.95144 -8.7859 -4.18804 -0.00313203 0.00270865 -0.124724 +EDGE3 421 471 4.61627 -0.0149304 -4.28252 -0.00417573 0.00381349 0.00135768 +EDGE3 420 471 4.14352 8.82043 -4.33821 0.0124943 0.00919296 0.125027 +EDGE3 421 470 3.93842 -8.79268 -4.20477 -0.000770601 -0.00734292 -0.123384 +EDGE3 422 472 4.59409 -0.00479256 -4.27888 0.00197236 -0.00371171 -0.0184485 +EDGE3 421 472 4.12511 8.8118 -4.35494 0.000422545 0.00368148 0.122169 +EDGE3 422 471 3.93486 -8.81784 -4.2068 0.00384048 0.000918364 -0.131299 +EDGE3 423 473 4.59109 -0.00810733 -4.28865 0.00389538 -0.00521222 -0.0027848 +EDGE3 422 473 4.132 8.83293 -4.35972 0.0109298 -0.000834119 0.120396 +EDGE3 423 472 3.93925 -8.84539 -4.20016 -0.00842516 -0.0043818 -0.128417 +EDGE3 424 474 4.5747 0.00993123 -4.30366 -0.00468356 -0.00570556 0.00748708 +EDGE3 423 474 4.10857 8.85248 -4.34576 0.00230146 -0.00441504 0.1237 +EDGE3 424 473 3.94637 -8.85219 -4.20209 0.00115356 -0.00195602 -0.129136 +EDGE3 425 475 4.56341 -0.0183107 -4.30547 -0.0020359 -0.0121482 0.00164963 +EDGE3 424 475 4.10606 8.87733 -4.38036 -0.00110174 0.00899314 0.126823 +EDGE3 425 474 3.92815 -8.86067 -4.2101 5.53004e-05 -0.00311513 -0.134242 +EDGE3 426 476 4.56994 0.00159592 -4.32369 0.000929 0.00504051 -0.000565551 +EDGE3 425 476 4.12035 8.87673 -4.39153 -0.00582304 -0.00127072 0.122396 +EDGE3 426 475 3.91723 -8.86576 -4.22157 0.00678782 -0.00402211 -0.118634 +EDGE3 427 477 4.56864 0.00289456 -4.30918 0.000121405 -0.00888252 0.00596433 +EDGE3 426 477 4.11309 8.90116 -4.39106 -0.0045902 -0.00242611 0.130372 +EDGE3 427 476 3.92001 -8.87364 -4.23141 -0.00409631 0.00700027 -0.12838 +EDGE3 428 478 4.57158 0.00272975 -4.31673 0.00835906 -0.00408993 0.00141278 +EDGE3 427 478 4.09772 8.89454 -4.40773 -0.011016 0.00103161 0.131098 +EDGE3 428 477 3.91741 -8.89377 -4.22206 0.00611481 0.00644024 -0.123466 +EDGE3 429 479 4.57127 -0.00691111 -4.3301 -0.00419164 0.00575553 -0.0036068 +EDGE3 428 479 4.09602 8.9265 -4.39571 0.000719131 0.000200779 0.127747 +EDGE3 429 478 3.90569 -8.90778 -4.24785 -0.00162401 0.000147973 -0.136635 +EDGE3 430 480 4.55261 -0.00113857 -4.33984 -0.00318463 0.000685871 0.00495338 +EDGE3 429 480 4.09953 8.92729 -4.40047 -0.0025605 0.00109224 0.115923 +EDGE3 430 479 3.91018 -8.91348 -4.23535 -0.00310413 0.00937015 -0.121017 +EDGE3 431 481 4.54296 -0.0089901 -4.33284 0.00651452 0.00232873 0.00160121 +EDGE3 430 481 4.08493 8.91848 -4.41336 -0.000377263 0.00222274 0.121871 +EDGE3 431 480 3.8981 -8.91632 -4.25143 -0.00187073 -0.00238809 -0.126192 +EDGE3 432 482 4.55021 0.0013497 -4.35025 0.00565387 0.000773725 -0.00299977 +EDGE3 431 482 4.08773 8.94182 -4.42437 -0.0082858 0.000749383 0.123238 +EDGE3 432 481 3.87714 -8.91516 -4.23181 -0.00767218 -0.00743687 -0.121052 +EDGE3 433 483 4.52841 0.00113511 -4.35059 -0.00509797 0.00205942 -0.00787933 +EDGE3 432 483 4.06779 8.91923 -4.44723 0.00314881 -0.0048247 0.132919 +EDGE3 433 482 3.90044 -8.95851 -4.25953 0.00287777 0.0106134 -0.125848 +EDGE3 434 484 4.52305 0.00786831 -4.37212 -0.00518343 -0.00339698 0.00123626 +EDGE3 433 484 4.07599 8.96601 -4.4383 -0.00224922 0.0086267 0.118641 +EDGE3 434 483 3.88846 -8.96219 -4.25681 0.000286184 -0.0041413 -0.125565 +EDGE3 435 485 4.52149 0.00147322 -4.34396 0.00897689 -0.0053617 -0.00118086 +EDGE3 434 485 4.04447 8.97963 -4.43907 -0.00145999 -0.00344838 0.124566 +EDGE3 435 484 3.85971 -8.96637 -4.24905 -0.00302946 -0.000109285 -0.133546 +EDGE3 436 486 4.52634 0.03519 -4.35239 -0.00149937 0.0065813 -0.00221448 +EDGE3 435 486 4.05402 8.98613 -4.44778 -0.0129389 -0.00277441 0.126159 +EDGE3 436 485 3.86802 -8.98886 -4.28116 -0.00343323 -0.00455391 -0.128546 +EDGE3 437 487 4.51556 -0.0174308 -4.36946 0.00718587 0.000195153 -0.0071827 +EDGE3 436 487 4.03696 9.00581 -4.43607 0.00434352 0.00421216 0.118677 +EDGE3 437 486 3.85336 -8.9885 -4.27646 0.000307028 0.00327935 -0.128313 +EDGE3 438 488 4.51371 0.0103637 -4.39627 0.00597743 0.000308835 0.000648539 +EDGE3 437 488 4.03109 8.9855 -4.46353 0.000925044 -0.00684544 0.125926 +EDGE3 438 487 3.86897 -9.00341 -4.28367 0.00351401 -0.0042042 -0.134643 +EDGE3 439 489 4.50965 0.00945107 -4.37629 0.000144386 -0.00192123 -0.00375691 +EDGE3 438 489 4.03323 9.02125 -4.45343 -0.00296393 -0.00650574 0.135581 +EDGE3 439 488 3.87451 -9.02421 -4.27698 -0.00534294 0.00440338 -0.130313 +EDGE3 440 490 4.49311 0.0147791 -4.40435 0.00184162 -0.0100709 0.00281962 +EDGE3 439 490 4.02623 9.0211 -4.48427 -0.00354644 -0.00564276 0.132606 +EDGE3 440 489 3.82562 -9.02862 -4.29873 -0.00236352 -0.00291452 -0.124412 +EDGE3 441 491 4.49268 -0.00723129 -4.39388 -0.00263583 -0.000839567 -0.00694676 +EDGE3 440 491 4.01074 9.04701 -4.48835 -0.00672183 0.00170294 0.127935 +EDGE3 441 490 3.84064 -9.03746 -4.29512 0.0063258 -0.00200503 -0.12287 +EDGE3 442 492 4.48798 -0.00984396 -4.41207 0.000775047 -0.00188949 -0.00468223 +EDGE3 441 492 4.0137 9.05408 -4.47383 -0.00111131 -0.0063851 0.121592 +EDGE3 442 491 3.83785 -9.04046 -4.30876 0.00115502 -0.00426462 -0.119116 +EDGE3 443 493 4.50133 0.00415041 -4.41984 -0.00411575 -0.00341031 0.00221174 +EDGE3 442 493 4.01253 9.06255 -4.47863 0.00200547 -0.008557 0.12637 +EDGE3 443 492 3.81151 -9.05489 -4.32351 0.00499192 0.0014407 -0.136849 +EDGE3 444 494 4.47089 0.00139535 -4.40078 -0.000681643 -0.0103149 -0.000446979 +EDGE3 443 494 4.00336 9.05927 -4.51307 -0.00135311 -6.37329e-05 0.128887 +EDGE3 444 493 3.82395 -9.07356 -4.31826 0.0021528 -0.00424393 -0.120894 +EDGE3 444 495 3.99071 9.08458 -4.49154 -0.00637525 -0.00353196 0.12485 +EDGE3 445 495 4.46811 -0.0123327 -4.42161 -0.00359029 -0.00150655 0.00459229 +EDGE3 445 494 3.81308 -9.07314 -4.32999 0.00235247 -0.00154702 -0.128873 +EDGE3 446 496 4.45273 -0.00402707 -4.42438 -0.00389881 0.000382871 0.0043404 +EDGE3 445 496 3.97484 9.08678 -4.50715 -0.00375917 -0.00236377 0.122741 +EDGE3 446 495 3.80636 -9.10172 -4.324 -0.000823194 0.00131497 -0.119686 +EDGE3 447 497 4.46925 -0.0101787 -4.41308 0.00469703 0.000859355 0.00793543 +EDGE3 446 497 3.95962 9.11366 -4.50147 -0.00352974 0.00711813 0.126732 +EDGE3 447 496 3.79934 -9.09034 -4.34004 -0.00219331 -0.0100989 -0.126014 +EDGE3 448 498 4.44804 -0.0249742 -4.44139 0.0063633 -0.0070511 0.00780944 +EDGE3 447 498 3.95208 9.10996 -4.52518 -0.00039552 0.00142602 0.122932 +EDGE3 448 497 3.80802 -9.08673 -4.35234 0.00275432 0.000294407 -0.124648 +EDGE3 449 499 4.46777 0.00433552 -4.43764 -0.00505844 -0.00320605 0.00360026 +EDGE3 448 499 3.96524 9.12588 -4.51926 0.00201026 -0.000536744 0.137997 +EDGE3 449 498 3.79614 -9.12137 -4.35973 -0.00191318 -0.00605343 -0.120238 +EDGE3 450 500 4.4438 0.000585628 -4.44406 0.0069077 -0.00167683 0.00114603 +EDGE3 449 500 3.97771 9.13241 -4.52192 0.00348611 -0.00070893 0.123483 +EDGE3 450 499 3.78446 -9.13064 -4.34753 -0.00505808 0.00789829 -0.118054 +EDGE3 451 501 4.42912 -0.00264163 -4.44882 -0.00265223 0.000170219 0.0041435 +EDGE3 450 501 3.93222 9.15503 -4.54872 -0.000430175 -0.000997469 0.120295 +EDGE3 451 500 3.78325 -9.1436 -4.36561 -0.00359195 0.000710573 -0.11229 +EDGE3 452 502 4.45112 0.0107525 -4.45139 0.00100503 -0.00010858 -0.00413616 +EDGE3 451 502 3.94303 9.15222 -4.53836 -0.00488579 0.0117283 0.127967 +EDGE3 452 501 3.76334 -9.15814 -4.38167 -0.00125983 0.00798383 -0.129368 +EDGE3 453 503 4.42806 -0.0105151 -4.46911 -0.0104299 0.00117303 0.0040258 +EDGE3 452 503 3.93866 9.1636 -4.53927 0.00755897 0.00604064 0.12815 +EDGE3 453 502 3.77073 -9.15601 -4.38349 0.00581606 -0.00716472 -0.133786 +EDGE3 454 504 4.4126 0.00441391 -4.45242 0.00118639 -0.00416583 -0.00264234 +EDGE3 453 504 3.92062 9.18911 -4.55048 -0.00474685 -0.000815412 0.131861 +EDGE3 454 503 3.76925 -9.17649 -4.37696 -0.0102395 -0.00307416 -0.123273 +EDGE3 455 505 4.41757 0.00292422 -4.46467 -0.00405902 -0.00211707 0.00315777 +EDGE3 454 505 3.92547 9.1748 -4.56186 0.00343033 0.00361293 0.122626 +EDGE3 455 504 3.75518 -9.18432 -4.374 -6.42109e-05 0.00268801 -0.127149 +EDGE3 456 506 4.41097 -0.00113746 -4.46722 0.00942265 -0.00184549 -0.00360706 +EDGE3 455 506 3.91444 9.18799 -4.5649 0.000493278 -0.0069317 0.127144 +EDGE3 456 505 3.74545 -9.18811 -4.37748 0.00674851 -0.00153417 -0.123841 +EDGE3 457 507 4.40455 0.0130242 -4.47205 6.43813e-05 -0.00112738 -0.000424206 +EDGE3 456 507 3.91188 9.20618 -4.55201 -6.05605e-06 -0.0066025 0.118733 +EDGE3 457 506 3.73126 -9.19583 -4.389 -0.00812589 0.00246594 -0.128159 +EDGE3 458 508 4.37647 -0.00130796 -4.49107 -0.000987593 0.000589256 -0.00694141 +EDGE3 457 508 3.88946 9.24017 -4.56841 0.00486678 -0.00617095 0.128088 +EDGE3 458 507 3.73603 -9.22472 -4.39566 0.00101462 -0.000488958 -0.120792 +EDGE3 459 509 4.39207 0.0113856 -4.50105 -0.00303555 -0.00246949 0.00334227 +EDGE3 458 509 3.88706 9.24298 -4.57662 -0.00998333 0.00115429 0.125516 +EDGE3 459 508 3.73141 -9.23563 -4.4077 0.000428822 0.00427186 -0.129317 +EDGE3 459 510 3.895 9.23709 -4.57898 -0.00491291 -0.00287953 0.123856 +EDGE3 460 510 4.3984 -0.00979754 -4.48633 0.00557091 -0.00109358 0.000345308 +EDGE3 461 511 4.36361 -0.00659598 -4.50844 0.000676541 0.00638383 0.00858618 +EDGE3 460 509 3.71566 -9.23746 -4.41098 0.00369497 -0.000396262 -0.123401 +EDGE3 461 510 3.71738 -9.25488 -4.39331 0.00796446 -0.000875389 -0.122843 +EDGE3 460 511 3.88384 9.27543 -4.57766 -0.00494227 -0.000301361 0.12233 +EDGE3 461 512 3.88296 9.25454 -4.58653 -0.00451259 0.00138487 0.134416 +EDGE3 462 512 4.38339 0.00444704 -4.51201 0.00733386 0.000242163 -0.00543636 +EDGE3 463 513 4.3856 -0.0258101 -4.52243 0.0105997 0.00201351 0.00971301 +EDGE3 462 511 3.69614 -9.26938 -4.41313 0.00413974 -0.00368415 -0.123013 +EDGE3 463 512 3.70904 -9.2544 -4.43359 -0.000204846 -0.00275828 -0.117515 +EDGE3 462 513 3.86324 9.29306 -4.60453 0.00712544 -0.00187496 0.124772 +EDGE3 463 514 3.86418 9.27529 -4.60182 0.00330037 -0.00723082 0.121644 +EDGE3 464 514 4.36616 0.0125572 -4.51997 0.000284976 0.00397017 -0.00164582 +EDGE3 465 515 4.35887 0.00697985 -4.53167 0.00811278 -0.00809916 -0.0050713 +EDGE3 464 513 3.68749 -9.26242 -4.41289 -0.000795482 -0.000341774 -0.110798 +EDGE3 465 514 3.68921 -9.28482 -4.4301 -0.00570997 -0.00271051 -0.125325 +EDGE3 464 515 3.87003 9.29496 -4.60722 0.000296508 0.000813475 0.128379 +EDGE3 465 516 3.85482 9.31504 -4.61277 -0.00166672 -0.00441831 0.121398 +EDGE3 466 516 4.34018 -0.0282718 -4.53392 -0.00221111 0.00169866 0.000807383 +EDGE3 467 517 4.32667 -0.00106913 -4.53293 -0.00226038 0.0117101 0.00297681 +EDGE3 466 515 3.68241 -9.30626 -4.43444 -0.00208536 0.00376548 -0.125412 +EDGE3 467 516 3.66666 -9.31421 -4.4412 -0.0101136 0.00469609 -0.128701 +EDGE3 466 517 3.8681 9.31121 -4.63525 -0.0038434 -0.000185829 0.126194 +EDGE3 467 518 3.84541 9.34398 -4.64247 0.00128541 0.00251905 0.130651 +EDGE3 468 518 4.34859 0.0192658 -4.53271 0.00216262 -0.00129017 0.00826521 +EDGE3 469 519 4.3493 -0.00126534 -4.53966 0.00205069 0.0046152 0.00155489 +EDGE3 468 517 3.66359 -9.31825 -4.43635 0.000810034 0.00571807 -0.12431 +EDGE3 469 518 3.67697 -9.31745 -4.45284 0.00277816 0.00186874 -0.130567 +EDGE3 468 519 3.8438 9.34069 -4.62501 -0.00235294 0.00475151 0.121809 +EDGE3 469 520 3.82799 9.34282 -4.6439 -0.00298332 0.0117143 0.128796 +EDGE3 470 520 4.32516 0.00862274 -4.57184 -0.00383357 -0.00454308 0.00280321 +EDGE3 470 519 3.65445 -9.32784 -4.44473 -0.0035448 -0.00569625 -0.134589 +EDGE3 471 521 4.34001 0.00303558 -4.55669 -0.000380407 -0.00632393 0.000473022 +EDGE3 470 521 3.81567 9.35759 -4.64269 -0.000587436 -0.00103594 0.121099 +EDGE3 472 522 4.30938 -0.0119973 -4.57881 0.00708179 0.00947614 -0.0061111 +EDGE3 471 520 3.67201 -9.34512 -4.44888 -0.00106011 -0.00276066 -0.126149 +EDGE3 472 521 3.63318 -9.34176 -4.46865 -9.26789e-05 -0.000961381 -0.126472 +EDGE3 471 522 3.82766 9.37451 -4.6587 -0.00177727 -0.0116751 0.130746 +EDGE3 472 523 3.83257 9.38047 -4.64007 -0.00318128 0.00987191 0.123525 +EDGE3 473 523 4.3162 0.00176307 -4.55985 -0.00130718 0.00262373 0.0030138 +EDGE3 474 524 4.32049 0.00278908 -4.58301 -0.000939691 -0.00328576 -0.0100397 +EDGE3 473 522 3.63936 -9.36162 -4.47485 -0.00484355 0.000803198 -0.125517 +EDGE3 473 524 3.81956 9.39898 -4.67051 -0.00293468 -0.00285522 0.126315 +EDGE3 474 523 3.64741 -9.38572 -4.49487 -0.00635023 0.00137556 -0.125314 +EDGE3 474 525 3.77696 9.40708 -4.67396 -0.000493666 0.00158248 0.128937 +EDGE3 475 525 4.30821 -0.00583262 -4.58187 0.00243817 0.00152706 -0.00307994 +EDGE3 476 526 4.28478 -0.0158121 -4.57053 -0.00267136 0.0019298 -0.00462347 +EDGE3 475 524 3.63194 -9.40371 -4.49264 0.00230255 0.00766336 -0.129974 +EDGE3 476 525 3.63028 -9.42441 -4.48978 0.00547564 0.00138931 -0.121167 +EDGE3 475 526 3.79781 9.42409 -4.66373 0.00768182 0.00430548 0.130575 +EDGE3 476 527 3.7752 9.42636 -4.66278 0.00299709 -0.00289345 0.120558 +EDGE3 477 527 4.29722 0.00982699 -4.58643 0.00711675 0.0093642 -0.00321283 +EDGE3 478 528 4.28258 0.0102563 -4.58456 0.00736021 -0.000607597 0.00286324 +EDGE3 477 526 3.62088 -9.41565 -4.50035 -0.00258348 -0.0124318 -0.129621 +EDGE3 478 527 3.6222 -9.43473 -4.50089 -0.00861207 -0.00689988 -0.134271 +EDGE3 477 528 3.77901 9.42006 -4.67541 -0.00226501 -0.00434855 0.132384 +EDGE3 479 529 4.27734 -0.00500611 -4.58956 -0.00240998 -0.00393679 0.00306961 +EDGE3 478 529 3.75822 9.43348 -4.69187 -0.00226591 -0.00056534 0.126643 +EDGE3 479 528 3.5918 -9.44003 -4.50055 0.00591585 0.00483288 -0.12523 +EDGE3 479 530 3.74922 9.45088 -4.71502 -0.00764642 0.0120798 0.124493 +EDGE3 480 530 4.28331 -0.00418513 -4.60804 -0.00150897 0.00938811 0.00311896 +EDGE3 481 531 4.25215 -0.00562922 -4.62958 -0.000474893 -0.00243374 -0.00444501 +EDGE3 480 529 3.58841 -9.45475 -4.48903 -0.0038548 0.00288203 -0.129007 +EDGE3 480 531 3.74744 9.45536 -4.70572 0.00301528 -0.00344631 0.122845 +EDGE3 481 530 3.58944 -9.46251 -4.51976 -0.00669757 -0.00339585 -0.126758 +EDGE3 481 532 3.74848 9.45992 -4.68522 -0.00478233 -0.00613862 0.124537 +EDGE3 482 532 4.28692 -0.00740014 -4.60512 0.00974222 0.00303854 -0.00184898 +EDGE3 483 533 4.25579 0.0160559 -4.63356 -0.00186941 0.00203941 0.0033389 +EDGE3 482 531 3.58979 -9.46506 -4.51784 -0.00241629 0.00373398 -0.139133 +EDGE3 483 532 3.5806 -9.48023 -4.52957 0.00668511 -0.00796709 -0.127545 +EDGE3 482 533 3.73554 9.48791 -4.7027 0.00451924 -0.00150199 0.129505 +EDGE3 483 534 3.74179 9.49896 -4.72329 0.000744549 -0.00037773 0.121851 +EDGE3 484 534 4.24796 -0.0108564 -4.639 -0.00334043 0.00396119 0.00340903 +EDGE3 485 535 4.23932 0.0137116 -4.63688 -0.00666614 0.00412243 -0.00384557 +EDGE3 484 533 3.56819 -9.48972 -4.53999 0.00295305 -0.0103521 -0.133445 +EDGE3 485 534 3.56229 -9.48717 -4.54422 0.000527135 0.00385807 -0.129048 +EDGE3 484 535 3.73621 9.5096 -4.72662 0.000157986 0.00269972 0.127155 +EDGE3 486 536 4.22894 -0.00304636 -4.66589 -0.000146676 -0.00475341 -0.00611295 +EDGE3 485 536 3.73143 9.52325 -4.72238 -0.00142931 0.000867925 0.130002 +EDGE3 486 535 3.56353 -9.50133 -4.53893 0.00790428 -0.00264756 -0.130664 +EDGE3 486 537 3.71054 9.53676 -4.7353 0.00364515 -0.000625419 0.125346 +EDGE3 487 537 4.22497 0.0064544 -4.63037 -0.0044213 0.00385964 -0.00224518 +EDGE3 488 538 4.20956 0.0123207 -4.66223 -2.06876e-05 -0.00236003 -0.0011884 +EDGE3 487 536 3.57192 -9.52547 -4.56132 0.00403437 0.0024417 -0.125672 +EDGE3 488 537 3.54561 -9.51902 -4.56 -0.00445842 0.00317633 -0.122704 +EDGE3 487 538 3.71751 9.53637 -4.73557 -0.00107065 -0.000273753 0.118399 +EDGE3 488 539 3.70762 9.54178 -4.76902 0.00687816 0.00122113 0.125447 +EDGE3 489 539 4.19527 -0.0171783 -4.64623 0.000182571 0.00784881 -0.00818993 +EDGE3 490 540 4.22681 0.00233117 -4.66005 -0.00333173 -0.00366281 0.00318824 +EDGE3 489 538 3.52823 -9.54011 -4.56461 0.000753414 -0.000422539 -0.132209 +EDGE3 490 539 3.5226 -9.53174 -4.54868 -0.00234797 0.00325414 -0.131106 +EDGE3 489 540 3.70962 9.55728 -4.7381 -0.00344725 -0.003182 0.126237 +EDGE3 490 541 3.68599 9.56212 -4.74471 0.00467137 -0.00216046 0.128399 +EDGE3 491 541 4.20719 -0.00644492 -4.68085 -0.00366979 0.00333009 0.00547133 +EDGE3 492 542 4.19209 -0.0149234 -4.67106 -0.00245462 0.0067297 -0.00556997 +EDGE3 491 540 3.54066 -9.56675 -4.5613 0.00587859 -0.00381476 -0.119791 +EDGE3 492 541 3.52642 -9.57361 -4.56059 0.00443117 0.00328704 -0.121653 +EDGE3 491 542 3.67528 9.58816 -4.77598 -0.00720201 0.00364224 0.12283 +EDGE3 492 543 3.67489 9.5732 -4.76549 0.00560097 -0.0042829 0.130689 +EDGE3 493 543 4.19582 0.000802126 -4.67935 -0.00354961 0.0017257 -0.00480723 +EDGE3 493 542 3.50962 -9.56515 -4.56927 -0.00327771 -0.00585462 -0.12849 +EDGE3 494 544 4.19389 0.000187639 -4.69407 -0.00128506 -0.00104836 -0.0051884 +EDGE3 493 544 3.67821 9.59169 -4.76552 -0.00346186 0.00582375 0.128592 +EDGE3 495 545 4.19281 0.00430629 -4.68089 0.000802375 0.000433807 0.00572064 +EDGE3 494 543 3.51611 -9.5846 -4.59299 0.00159228 -0.00784582 -0.12186 +EDGE3 495 544 3.50299 -9.58261 -4.57028 0.00142152 0.00601806 -0.123879 +EDGE3 494 545 3.68138 9.60775 -4.79481 0.00722174 -0.00141838 0.126819 +EDGE3 496 546 4.18838 -0.00399047 -4.68092 0.00143343 0.0062599 0.00524899 +EDGE3 495 546 3.66433 9.61194 -4.78087 -0.00106899 -0.00168743 0.121679 +EDGE3 496 545 3.49632 -9.59036 -4.60046 -0.00276472 -0.0055603 -0.132577 +EDGE3 497 547 4.1804 -0.013696 -4.68442 0.00199332 -0.00540211 -0.00127077 +EDGE3 496 547 3.6764 9.62388 -4.77141 0.00236224 0.00190691 0.131245 +EDGE3 497 546 3.48576 -9.62548 -4.59881 0.0031902 -0.00110833 -0.120974 +EDGE3 498 548 4.16518 0.0064734 -4.70278 0.00682253 0.0055233 -0.00592631 +EDGE3 497 548 3.6278 9.63946 -4.80134 -0.00302253 -0.00392766 0.13435 +EDGE3 498 547 3.47223 -9.6108 -4.60246 0.00466718 -0.00328426 -0.119694 +EDGE3 499 549 4.15791 -0.00732062 -4.70741 -0.00197779 0.00039554 -0.00708716 +EDGE3 498 549 3.65651 9.63989 -4.79925 0.00227211 -0.00203024 0.126557 +EDGE3 499 548 3.47697 -9.62217 -4.61775 0.00746111 -0.00851916 -0.126831 +EDGE3 500 550 4.14949 0.0154234 -4.721 -0.000617331 0.0029541 0.00823078 +EDGE3 499 550 3.63826 9.6678 -4.79371 -0.000905687 -0.00170521 0.120723 +EDGE3 500 549 3.46885 -9.64332 -4.62537 0.0005706 -0.00111207 -0.123795 +EDGE3 501 551 4.15923 0.00451624 -4.71473 0.00504002 -0.00858697 0.00572171 +EDGE3 500 551 3.6321 9.66187 -4.80008 0.00849207 -0.00533413 0.122748 +EDGE3 501 550 3.4548 -9.65727 -4.62511 -0.00584993 -0.0066021 -0.119783 +EDGE3 502 552 4.1427 0.00212205 -4.72175 -0.00115117 0.00230963 0.00683042 +EDGE3 501 552 3.62452 9.66402 -4.82595 0.00472735 0.00336391 0.126726 +EDGE3 502 551 3.46323 -9.66807 -4.63206 -0.00355687 0.010865 -0.115082 +EDGE3 503 553 4.14482 0.00119137 -4.73145 0.0121461 -0.000265577 -0.0106829 +EDGE3 502 553 3.6184 9.68669 -4.80189 0.0022467 0.00214415 0.122719 +EDGE3 503 552 3.43517 -9.70183 -4.61193 -0.00530769 -0.00296587 -0.127946 +EDGE3 504 554 4.12818 -0.00619947 -4.7402 0.00627131 -0.0106814 -0.00339176 +EDGE3 503 554 3.58666 9.69888 -4.83354 0.00315743 0.00328739 0.125201 +EDGE3 504 553 3.43126 -9.69907 -4.63824 -0.00150223 0.000758634 -0.124385 +EDGE3 505 555 4.11822 0.00267496 -4.73283 0.00330058 -0.00252665 -0.00278923 +EDGE3 504 555 3.59196 9.69217 -4.84122 -0.00492016 0.00518678 0.121755 +EDGE3 505 554 3.44055 -9.68527 -4.64115 -0.000992927 -0.0070481 -0.12154 +EDGE3 506 556 4.11654 -0.0124659 -4.73846 -0.000159192 0.00541983 0.00189885 +EDGE3 505 556 3.58536 9.70737 -4.832 0.00486707 0.00549397 0.127502 +EDGE3 506 555 3.41037 -9.69422 -4.6475 -0.000150767 -0.00146194 -0.134125 +EDGE3 507 557 4.10179 0.00696934 -4.73075 0.00132416 -0.00953774 0.00269777 +EDGE3 506 557 3.58605 9.72679 -4.84834 -0.00103521 0.00207854 0.119438 +EDGE3 507 556 3.40924 -9.7178 -4.63544 -0.00518813 -0.00122171 -0.131038 +EDGE3 508 558 4.1035 -0.00438821 -4.73318 0.00219785 -0.00578937 -0.00173877 +EDGE3 507 558 3.58542 9.7341 -4.86189 0.00767791 -0.00920081 0.128817 +EDGE3 508 557 3.4099 -9.71971 -4.66645 0.00115426 -0.00621893 -0.122215 +EDGE3 509 559 4.09675 -0.0135113 -4.7546 0.00398875 0.00344973 0.000694147 +EDGE3 508 559 3.56288 9.75692 -4.85822 0.00204337 0.00121208 0.130158 +EDGE3 509 558 3.42362 -9.74812 -4.65772 -0.00289663 0.00404109 -0.117528 +EDGE3 510 560 4.09132 -0.00672032 -4.7601 -0.000441616 -0.00222122 0.00399146 +EDGE3 509 560 3.5858 9.76069 -4.87611 -0.00371683 -0.00239476 0.122082 +EDGE3 510 559 3.40311 -9.73637 -4.65841 -0.00314021 -0.00395072 -0.124906 +EDGE3 511 561 4.08194 -0.000697243 -4.75798 0.00517048 0.00125971 -0.00370729 +EDGE3 510 561 3.53331 9.78179 -4.8498 0.00553035 -0.00123634 0.122129 +EDGE3 511 560 3.38376 -9.76635 -4.66545 0.0129425 -0.0127281 -0.11754 +EDGE3 512 562 4.07729 0.011889 -4.78732 0.00239271 -0.00245931 -0.00865113 +EDGE3 511 562 3.55326 9.78063 -4.86914 -0.0199118 0.00128986 0.126518 +EDGE3 512 561 3.388 -9.77349 -4.68642 0.00187042 0.00602555 -0.124018 +EDGE3 513 563 4.08893 -0.00865785 -4.77604 0.00741595 0.00456975 0.00479194 +EDGE3 512 563 3.5472 9.76598 -4.87289 0.00575902 -0.00916243 0.125045 +EDGE3 513 562 3.37588 -9.77711 -4.68021 0.00186833 -0.00234762 -0.132934 +EDGE3 514 564 4.07738 -0.0094426 -4.80382 -0.00576292 0.00392908 0.0012686 +EDGE3 513 564 3.5536 9.78408 -4.8814 0.00503503 -0.00893179 0.127353 +EDGE3 514 563 3.34177 -9.7796 -4.68949 -0.00317643 -0.00508339 -0.123622 +EDGE3 515 565 4.07775 0.000977889 -4.79526 -0.000697836 0.00438713 -0.00336755 +EDGE3 515 564 3.37794 -9.79214 -4.68379 0.00737673 -0.0018037 -0.127326 +EDGE3 514 565 3.53188 9.80959 -4.87714 -0.00267239 -0.00109422 0.123886 +EDGE3 516 566 4.07758 -0.00118916 -4.78617 -0.000585809 0.00349573 0.000664776 +EDGE3 515 566 3.52075 9.80708 -4.91457 -0.000115363 0.00274199 0.119602 +EDGE3 516 565 3.35629 -9.8012 -4.69551 0.000415383 -0.00196459 -0.131364 +EDGE3 517 567 4.03888 -0.00214749 -4.79807 0.00338858 -0.000757947 -0.00465044 +EDGE3 516 567 3.5127 9.82092 -4.88371 -0.00729674 0.00352403 0.121271 +EDGE3 517 566 3.36555 -9.81436 -4.6996 -0.00159854 0.00406745 -0.135273 +EDGE3 518 568 4.04904 -0.00706546 -4.81248 -0.00371939 -0.00262885 0.00114072 +EDGE3 517 568 3.5215 9.84508 -4.90148 0.000980446 -0.00409751 0.124936 +EDGE3 518 567 3.33685 -9.81396 -4.71451 0.000686678 0.00804762 -0.130607 +EDGE3 519 569 4.0575 0.00925076 -4.81218 -0.00221392 0.00409576 0.000819555 +EDGE3 518 569 3.49986 9.84985 -4.92138 -0.00161288 -0.00322739 0.124533 +EDGE3 519 568 3.33865 -9.83495 -4.70684 -0.000532094 0.000538281 -0.122139 +EDGE3 520 570 4.04302 -0.00637454 -4.7988 0.00614663 -0.0110641 0.00561409 +EDGE3 519 570 3.48767 9.8622 -4.89698 0.00398223 -0.00198312 0.116895 +EDGE3 520 569 3.3241 -9.85331 -4.70272 0.00107714 0.00143828 -0.126696 +EDGE3 521 571 4.03041 -0.00642155 -4.82722 0.0024287 0.00490068 -0.000878068 +EDGE3 520 571 3.49468 9.85249 -4.92475 -0.0104841 0.00222573 0.118492 +EDGE3 521 570 3.33575 -9.84127 -4.70976 0.00273546 -0.00792195 -0.128145 +EDGE3 522 572 4.02111 0.0112725 -4.80805 0.0115583 0.00253466 -0.00517774 +EDGE3 521 572 3.47232 9.87783 -4.90207 0.00539142 -0.000694509 0.127818 +EDGE3 522 571 3.33086 -9.86013 -4.73736 -0.00412435 -0.00968588 -0.126023 +EDGE3 523 573 4.01974 -0.00441439 -4.82157 -0.00235696 -0.00193668 0.00793338 +EDGE3 522 573 3.48737 9.8839 -4.92953 0.0034771 0.00250372 0.123863 +EDGE3 523 572 3.2987 -9.84753 -4.74058 -4.80784e-05 -0.00302448 -0.139368 +EDGE3 524 574 3.99768 -0.00125708 -4.83461 -0.00116032 -0.00430551 -0.000839172 +EDGE3 523 574 3.4738 9.89469 -4.93055 0.00357332 0.00290221 0.13018 +EDGE3 524 573 3.31039 -9.89349 -4.74799 -0.00443884 0.00358139 -0.118403 +EDGE3 525 575 4.00631 0.00860313 -4.83945 0.00185717 -0.000311803 0.00689974 +EDGE3 525 574 3.31155 -9.90603 -4.74934 -0.00567759 -0.00894816 -0.124262 +EDGE3 524 575 3.47284 9.90683 -4.93887 -0.00206223 0.00111991 0.122986 +EDGE3 526 576 3.98852 -0.00255505 -4.84052 0.000411446 0.00159472 -0.00136491 +EDGE3 525 576 3.44174 9.91444 -4.93969 0.00345647 0.00913779 0.126618 +EDGE3 526 575 3.30788 -9.9142 -4.74332 -0.00199853 -0.00151992 -0.119616 +EDGE3 527 577 3.9894 0.0028358 -4.84881 0.000360983 0.000411097 -0.00887963 +EDGE3 526 577 3.4487 9.91287 -4.96418 0.00468098 -0.0105841 0.11479 +EDGE3 527 576 3.30238 -9.91384 -4.75431 -0.000778514 0.00295694 -0.127775 +EDGE3 528 578 3.96655 0.00306449 -4.85734 -0.00500999 -0.00325866 0.00764169 +EDGE3 527 578 3.42914 9.92161 -4.97259 0.000294414 -0.00186577 0.129655 +EDGE3 528 577 3.2983 -9.93021 -4.74861 0.00140282 0.00530942 -0.128108 +EDGE3 529 579 3.98042 -0.00224137 -4.85618 -0.00315555 -0.0049015 -0.00592833 +EDGE3 528 579 3.43629 9.93668 -4.97002 -0.00340408 -0.0035769 0.122598 +EDGE3 529 578 3.27164 -9.95273 -4.76841 -0.00121472 -0.00155622 -0.127515 +EDGE3 530 580 3.97888 -0.00333401 -4.84897 -0.00075931 0.00801667 -0.00267996 +EDGE3 529 580 3.43819 9.95929 -4.95262 -0.0043934 -0.00258725 0.12916 +EDGE3 530 579 3.25464 -9.93401 -4.76449 -0.00392042 -0.00344075 -0.123831 +EDGE3 531 581 3.95683 -0.00908862 -4.86583 -0.00449404 0.00075964 -0.00381363 +EDGE3 530 581 3.42423 9.94719 -4.95846 -0.000973163 0.00220244 0.123455 +EDGE3 531 580 3.28234 -9.97361 -4.78189 -0.00539012 0.00892801 -0.121404 +EDGE3 532 582 3.97364 -0.0157707 -4.88499 -0.00798657 0.00582659 0.00151331 +EDGE3 531 582 3.41861 9.96168 -4.9815 -0.00109205 -0.00729404 0.119546 +EDGE3 532 581 3.26398 -9.97311 -4.79553 0.000229185 0.00530905 -0.125368 +EDGE3 533 583 3.96646 0.00352582 -4.87948 -0.00203322 0.00128946 0.00147149 +EDGE3 532 583 3.40279 9.982 -4.9785 0.00369907 0.00399036 0.124626 +EDGE3 533 582 3.25613 -9.98058 -4.77576 -0.00172696 0.00638431 -0.118459 +EDGE3 534 584 3.95183 0.0176136 -4.89655 -0.00162179 0.00771819 -0.00298993 +EDGE3 533 584 3.40787 9.97056 -4.96955 -0.000648277 0.00375655 0.129307 +EDGE3 534 583 3.24176 -9.98736 -4.77469 0.00201472 0.00952813 -0.121386 +EDGE3 535 585 3.92862 0.0147385 -4.88557 0.00419773 0.00676158 0.000431731 +EDGE3 534 585 3.39451 9.99785 -4.98515 0.00151308 -0.00629905 0.122634 +EDGE3 535 584 3.2398 -9.99751 -4.78282 -0.0110348 -0.00340262 -0.124769 +EDGE3 536 586 3.92612 -0.00835786 -4.88821 -0.0058865 0.00565802 -0.0012982 +EDGE3 535 586 3.37856 10.026 -5.00695 0.00179954 -0.0010196 0.12231 +EDGE3 536 585 3.22657 -10.0146 -4.78616 0.005602 0.000799481 -0.126458 +EDGE3 537 587 3.93775 -0.0147492 -4.90017 -0.00396336 -0.000883943 0.000830095 +EDGE3 536 587 3.38168 10.0041 -4.9902 -0.00366044 0.00208036 0.116929 +EDGE3 537 586 3.2214 -9.99115 -4.80297 0.00755293 -0.00967819 -0.118324 +EDGE3 538 588 3.92128 0.00339189 -4.91585 -0.00720396 0.00557486 -0.000780481 +EDGE3 537 588 3.38609 10.0247 -4.99953 -0.00829706 -0.000996155 0.114736 +EDGE3 538 587 3.24326 -10.0285 -4.7985 0.0015965 0.00458703 -0.127058 +EDGE3 539 589 3.91256 -0.00816618 -4.9049 0.0141676 0.00195063 0.000699316 +EDGE3 538 589 3.3644 10.0309 -5.01313 0.000377384 0.00168912 0.12653 +EDGE3 539 588 3.21191 -10.0099 -4.8176 -0.00192969 -0.00487285 -0.116265 +EDGE3 540 590 3.91937 -0.015299 -4.92356 -0.0013048 -0.000742081 -0.00764226 +EDGE3 539 590 3.35164 10.0534 -5.00686 0.00203989 0.00363289 0.136568 +EDGE3 540 589 3.20688 -10.0393 -4.80559 0.00383257 -0.00789076 -0.126794 +EDGE3 541 591 3.90686 0.0236799 -4.93637 -0.000124232 -0.00810089 0.000212981 +EDGE3 540 591 3.33141 10.0519 -5.02584 -0.00431859 -0.000653587 0.128539 +EDGE3 541 590 3.20409 -10.0564 -4.81636 0.00269504 -0.00489055 -0.12779 +EDGE3 542 592 3.92179 0.0106822 -4.92495 -0.00154363 -0.0117366 0.0014445 +EDGE3 541 592 3.35001 10.0616 -5.02564 0.0011433 -0.00406623 0.121512 +EDGE3 542 591 3.19207 -10.0552 -4.8195 0.00374529 0.000602474 -0.135443 +EDGE3 543 593 3.89432 0.0139376 -4.93201 -0.00343457 -0.00777345 0.000660048 +EDGE3 542 593 3.35389 10.0716 -5.01827 -0.000140461 -0.00129354 0.122699 +EDGE3 543 592 3.16207 -10.0608 -4.84113 0.00155928 -0.00861627 -0.129089 +EDGE3 544 594 3.87678 0.0114387 -4.92657 0.00840292 0.0158842 -0.00248239 +EDGE3 543 594 3.32907 10.0796 -5.04344 -0.000867459 -0.000601082 0.130037 +EDGE3 544 593 3.18442 -10.0832 -4.82374 -0.00160502 -0.00760596 -0.131887 +EDGE3 545 595 3.8674 0.00932061 -4.93534 0.00383057 0.000584725 0.00553015 +EDGE3 544 595 3.33795 10.1035 -5.01982 0.00360112 0.00320271 0.126171 +EDGE3 545 594 3.1608 -10.0877 -4.8414 -0.00644328 0.00190853 -0.130516 +EDGE3 546 596 3.8645 0.0193658 -4.94495 0.00141499 -0.00230874 -0.00773035 +EDGE3 545 596 3.33422 10.0995 -5.04725 0.00468276 0.00223843 0.122468 +EDGE3 546 595 3.17125 -10.088 -4.8586 -0.00158982 -0.000231364 -0.134238 +EDGE3 547 597 3.85686 0.0151523 -4.95261 -0.0079788 -0.0100979 -0.00342357 +EDGE3 546 597 3.31763 10.1204 -5.04773 -0.00321789 -0.00884067 0.118385 +EDGE3 547 596 3.14958 -10.1079 -4.84755 0.00179919 0.00277049 -0.128513 +EDGE3 548 598 3.8609 -5.36797e-05 -4.93516 -0.00178044 -0.00712289 0.00210986 +EDGE3 547 598 3.31281 10.1229 -5.05602 0.0114115 0.00266677 0.124151 +EDGE3 548 597 3.1279 -10.1019 -4.85694 -0.00242146 0.00436408 -0.125472 +EDGE3 549 599 3.87529 0.00888275 -4.96046 0.00982521 -0.00479767 -0.00124262 +EDGE3 549 598 3.12972 -10.1199 -4.85243 -0.000302915 0.000257775 -0.127534 +EDGE3 548 599 3.30019 10.1286 -5.04082 0.00296697 0.0016437 0.121842 +EDGE3 549 600 3.30158 10.1297 -5.06788 -0.00131834 -0.00345372 0.126114 +EDGE3 550 600 3.82823 0.00655218 -4.96854 -0.00495529 0.00942092 -0.00329515 +EDGE3 551 601 3.84805 0.00374558 -4.96947 -0.00678603 0.000336017 0.00626651 +EDGE3 550 599 3.14777 -10.1389 -4.8583 -0.000786435 -0.00438039 -0.121681 +EDGE3 551 600 3.11776 -10.1534 -4.87678 -0.00466327 -0.00131053 -0.122787 +EDGE3 550 601 3.2854 10.1505 -5.09028 0.00219828 0.00071179 0.123601 +EDGE3 551 602 3.28227 10.1398 -5.07079 0.00453387 0.00235954 0.133931 +EDGE3 552 602 3.82007 -0.00293255 -4.97248 -0.00974981 0.00157341 0.00148268 +EDGE3 553 603 3.83165 -0.00687894 -4.98651 0.00200402 1.44298e-05 -0.00257029 +EDGE3 552 601 3.11583 -10.1377 -4.86241 -0.00682819 0.00801697 -0.125693 +EDGE3 552 603 3.27561 10.1659 -5.07376 0.00891808 0.00378381 0.129857 +EDGE3 553 602 3.12703 -10.1447 -4.88694 -0.0034448 0.00144459 -0.120709 +EDGE3 553 604 3.25717 10.1693 -5.07588 0.0083614 -0.00285395 0.121852 +EDGE3 554 604 3.82333 -0.00396218 -4.9956 -0.0079467 -0.00474782 -0.00198388 +EDGE3 555 605 3.81496 -0.00794495 -4.986 -0.00301686 0.011294 0.0102581 +EDGE3 554 603 3.12033 -10.1597 -4.87839 0.00143811 -0.00540824 -0.124863 +EDGE3 555 604 3.10646 -10.1744 -4.89193 0.000975086 0.00457002 -0.128631 +EDGE3 554 605 3.25709 10.1716 -5.0799 -0.00564956 -0.00308346 0.126355 +EDGE3 555 606 3.24774 10.1906 -5.09857 0.00373184 0.00204915 0.120407 +EDGE3 556 606 3.80716 0.00550729 -4.99073 0.00994994 0.00100582 0.0016069 +EDGE3 557 607 3.79638 -0.0191686 -4.98166 -0.00292982 -0.00212358 0.00154171 +EDGE3 556 605 3.10187 -10.1969 -4.89018 -0.00267339 0.00290024 -0.125933 +EDGE3 557 606 3.08767 -10.1849 -4.89557 0.00663556 -0.00332835 -0.11929 +EDGE3 556 607 3.245 10.2067 -5.09445 -0.00819503 0.00387711 0.12444 +EDGE3 557 608 3.22453 10.2111 -5.10585 0.00740736 -0.00577389 0.122797 +EDGE3 558 608 3.78735 0.0174316 -5.00772 0.00555325 -0.0021304 -0.00868195 +EDGE3 559 609 3.76988 0.00436843 -5.01031 -0.0079796 -0.000111677 0.000475844 +EDGE3 558 607 3.10225 -10.2009 -4.87015 -0.00492774 0.00106625 -0.13108 +EDGE3 558 609 3.22077 10.2347 -5.09677 0.00147674 -0.0139149 0.135386 +EDGE3 559 608 3.08143 -10.2167 -4.90211 -0.00663998 0.00242962 -0.127638 +EDGE3 559 610 3.20519 10.2288 -5.07939 0.00780585 -0.00680841 0.120996 +EDGE3 560 610 3.77899 0.0159936 -5.01243 -0.00346712 0.00465191 -0.00267682 +EDGE3 561 611 3.76255 -0.00859258 -5.01438 -0.00322155 -0.000337761 -0.00172883 +EDGE3 560 609 3.08385 -10.2172 -4.90957 0.00026934 -0.00189635 -0.125366 +EDGE3 560 611 3.19878 10.2787 -5.10731 -0.00205786 -0.00136652 0.128817 +EDGE3 561 610 3.06865 -10.2328 -4.92088 0.00469559 0.00834797 -0.124568 +EDGE3 561 612 3.21536 10.2541 -5.11478 0.00219086 0.0015216 0.129281 +EDGE3 562 612 3.77417 0.0118356 -5.02251 -0.000348278 -0.00342046 0.00329064 +EDGE3 562 611 3.06334 -10.2568 -4.91926 -0.00193059 0.000267828 -0.129755 +EDGE3 563 613 3.76559 0.0110292 -5.01811 0.00719274 0.00452825 0.00441772 +EDGE3 563 612 3.06096 -10.2484 -4.92205 -0.00376813 -0.00689205 -0.128626 +EDGE3 562 613 3.17976 10.267 -5.1434 -0.000497215 0.0025646 0.125523 +EDGE3 563 614 3.20497 10.2629 -5.13571 0.00368702 -0.00216351 0.12264 +EDGE3 564 614 3.75796 0.00957941 -5.03742 -0.000391669 0.0014036 0.00441769 +EDGE3 565 615 3.73867 -0.00936694 -5.03895 -0.0103294 -0.00753822 -0.00467508 +EDGE3 564 613 3.04242 -10.2546 -4.92979 0.00549757 -0.00508619 -0.12855 +EDGE3 564 615 3.1885 10.2705 -5.12991 -0.00743847 -0.000538305 0.126152 +EDGE3 565 614 3.03687 -10.2794 -4.93008 0.00178389 -0.0069832 -0.122606 +EDGE3 566 616 3.74387 0.00714648 -5.03446 -0.00149376 -0.00746568 -0.00366393 +EDGE3 565 616 3.18992 10.2972 -5.1382 -0.00354582 0.00144486 0.128721 +EDGE3 566 615 3.04177 -10.2742 -4.93843 -0.0008827 0.0129637 -0.121033 +EDGE3 566 617 3.18538 10.2947 -5.15304 0.00290427 0.000370332 0.121245 +EDGE3 567 617 3.73523 -0.0204864 -5.02594 0.00961214 0.00732521 -0.00130556 +EDGE3 568 618 3.72462 0.00671839 -5.04447 -0.00854892 0.00566754 -0.00756221 +EDGE3 567 616 3.0325 -10.3085 -4.94576 -0.00189192 0.00911211 -0.124694 +EDGE3 568 617 3.01177 -10.3018 -4.94888 -0.00222413 0.00441774 -0.131421 +EDGE3 567 618 3.18261 10.3183 -5.1515 -0.000351505 -0.00117082 0.12455 +EDGE3 569 619 3.73103 -0.00532177 -5.03098 -0.00250045 0.00188954 -0.00249899 +EDGE3 568 619 3.17457 10.3165 -5.14468 0.00937468 0.00043789 0.127563 +EDGE3 569 618 3.03641 -10.3005 -4.95345 -0.00407424 0.00174603 -0.120663 +EDGE3 569 620 3.15358 10.3335 -5.15428 -0.000329511 0.00868366 0.126232 +EDGE3 570 620 3.7177 -0.0121787 -5.06965 -0.00247778 -0.00158323 -0.0051888 +EDGE3 571 621 3.7139 0.0111902 -5.05937 0.00388199 -0.00336577 -0.000177325 +EDGE3 570 619 3.01758 -10.3096 -4.95128 0.00495331 0.00504841 -0.125925 +EDGE3 571 620 2.99372 -10.3217 -4.95494 -0.00232028 0.000374211 -0.125192 +EDGE3 570 621 3.13857 10.3379 -5.16669 -0.00387291 -0.00132343 0.127286 +EDGE3 572 622 3.70756 -0.00695913 -5.0624 -0.000777122 0.00600515 -0.00493467 +EDGE3 571 622 3.14573 10.3369 -5.17198 0.00910736 0.00855032 0.118944 +EDGE3 572 621 2.99503 -10.3465 -4.96314 -0.00895931 -0.011011 -0.119544 +EDGE3 572 623 3.14076 10.3486 -5.16924 -0.000611718 0.00468037 0.125264 +EDGE3 573 623 3.71084 -0.0105865 -5.07073 -0.00604556 -0.00640938 -0.0011717 +EDGE3 574 624 3.69457 -0.0044826 -5.08854 -0.00657541 -0.00354436 -0.00333611 +EDGE3 573 622 2.98761 -10.3322 -4.97437 0.00166695 0.00332842 -0.116772 +EDGE3 573 624 3.11966 10.3604 -5.16885 0.00527336 -0.000352594 0.122276 +EDGE3 574 623 2.97741 -10.3474 -4.97412 -0.000487101 0.00270548 -0.122328 +EDGE3 574 625 3.11555 10.363 -5.17012 -0.000287521 -0.00637485 0.129212 +EDGE3 575 625 3.6961 0.0134447 -5.07345 -0.000532977 -0.0026263 0.00361198 +EDGE3 576 626 3.68365 0.00017119 -5.08578 -0.00146287 0.00459213 -0.00443297 +EDGE3 575 624 2.98517 -10.3666 -4.97705 0.0024264 0.00110496 -0.126456 +EDGE3 576 625 2.98019 -10.3618 -4.97615 -0.000155968 -0.00152001 -0.122704 +EDGE3 575 626 3.11702 10.4019 -5.18667 -0.00511362 -0.0106532 0.117063 +EDGE3 576 627 3.10521 10.3876 -5.18565 -0.00249675 -0.00208774 0.124722 +EDGE3 577 627 3.6809 0.0239462 -5.08164 -0.00643921 -0.000466334 0.00238767 +EDGE3 578 628 3.67222 0.000951464 -5.11166 -0.00785244 -0.000608851 -0.00554089 +EDGE3 577 626 2.95597 -10.336 -4.9897 -0.0092191 0.00396602 -0.128216 +EDGE3 577 628 3.10356 10.3848 -5.19834 0.00205978 0.00634897 0.135653 +EDGE3 578 627 2.9646 -10.3742 -5.00093 -0.00150028 -0.00993813 -0.125634 +EDGE3 578 629 3.08427 10.4007 -5.20206 -0.00647998 -0.0096042 0.118611 +EDGE3 579 629 3.66583 0.0130949 -5.098 0.000609887 -0.00325081 -0.00931334 +EDGE3 580 630 3.67295 0.0131679 -5.09729 0.00110559 0.00492199 0.00092105 +EDGE3 579 628 2.93627 -10.4121 -4.99627 -0.00206394 -0.00975469 -0.118776 +EDGE3 580 629 2.94789 -10.4023 -5.00679 -0.00792868 -0.00258082 -0.12401 +EDGE3 579 630 3.09527 10.4138 -5.19304 -0.00116282 -0.00424251 0.117442 +EDGE3 580 631 3.07694 10.398 -5.23034 -0.00612778 -0.00892822 0.122879 +EDGE3 581 631 3.6455 0.023339 -5.11564 0.00728923 -0.00172121 0.000856054 +EDGE3 582 632 3.64234 0.00738819 -5.11118 0.00696971 -0.000579707 -0.00555056 +EDGE3 581 630 2.92739 -10.4046 -5.01324 0.0113205 -0.00033522 -0.122932 +EDGE3 581 632 3.05946 10.4342 -5.20567 0.00447077 -0.00180377 0.125802 +EDGE3 582 631 2.92184 -10.4195 -5.00784 -0.000359283 -0.00155658 -0.121677 +EDGE3 582 633 3.06478 10.4327 -5.22456 -0.000264441 -0.00362871 0.130468 +EDGE3 583 633 3.63134 0.022564 -5.13015 0.000576548 -0.00315635 0.007846 +EDGE3 584 634 3.63912 -0.006232 -5.13529 0.00606761 0.00815455 0.00719029 +EDGE3 583 632 2.91582 -10.4265 -5.00227 -0.00851286 0.011639 -0.128906 +EDGE3 584 633 2.90607 -10.4545 -5.01848 -0.00155885 -0.00314861 -0.125224 +EDGE3 583 634 3.04247 10.4505 -5.2147 -0.0109566 -0.00519447 0.119398 +EDGE3 585 635 3.62388 -0.0103171 -5.11905 -0.000505142 0.00111259 -0.00455332 +EDGE3 584 635 3.0457 10.4479 -5.22938 0.00415102 0.0119525 0.133848 +EDGE3 585 634 2.89954 -10.427 -5.03319 0.000255717 0.00268095 -0.1274 +EDGE3 585 636 3.04478 10.4557 -5.23901 -0.00837509 0.00527005 0.122421 +EDGE3 586 636 3.62663 0.0106495 -5.14216 -4.30652e-08 0.00270637 -0.00888913 +EDGE3 586 635 2.90381 -10.4347 -5.01108 0.000910584 0.00299108 -0.12414 +EDGE3 587 637 3.60706 0.0147326 -5.13862 -0.0025231 0.00264951 0.00225619 +EDGE3 586 637 3.02111 10.4734 -5.24915 -0.00187728 -0.00471263 0.129977 +EDGE3 587 636 2.88693 -10.4593 -5.03275 0.00608968 0.00411299 -0.121216 +EDGE3 588 638 3.60748 -0.00485091 -5.14359 -0.00187241 -4.69797e-05 0.00794143 +EDGE3 587 638 3.01032 10.4912 -5.25429 0.00236286 0.00277458 0.130541 +EDGE3 588 637 2.87738 -10.4502 -5.04413 0.00402322 -0.00747167 -0.124814 +EDGE3 589 639 3.58888 0.000664792 -5.15325 0.00428066 -0.00340252 -0.00486861 +EDGE3 588 639 3.0199 10.4984 -5.24282 -0.000408244 -0.00311866 0.124571 +EDGE3 589 638 2.86526 -10.4766 -5.04917 0.00161265 -0.00452018 -0.12592 +EDGE3 590 640 3.59252 0.00125891 -5.14594 -0.00152935 -0.00495138 0.00128097 +EDGE3 589 640 3.02296 10.4972 -5.25408 0.0042626 0.00839083 0.129212 +EDGE3 590 639 2.87252 -10.4812 -5.04266 -0.00379797 -0.000198726 -0.130765 +EDGE3 591 641 3.59079 0.016206 -5.16173 0.00857632 -0.00115809 -0.00431113 +EDGE3 590 641 3.00219 10.5143 -5.26455 -0.00712749 0.000362911 0.124272 +EDGE3 591 640 2.87344 -10.498 -5.05434 -0.00208811 -0.00228114 -0.121919 +EDGE3 592 642 3.57683 -0.0134408 -5.15345 -0.00209095 -0.00166858 -0.00441533 +EDGE3 591 642 2.98732 10.5103 -5.24486 0.0101411 0.00402231 0.123659 +EDGE3 592 641 2.85375 -10.5002 -5.05202 -0.00441883 -0.00983458 -0.136898 +EDGE3 593 643 3.58094 0.01018 -5.15716 0.00156996 0.001886 0.00680967 +EDGE3 592 643 2.99781 10.5203 -5.2575 0.000973076 -0.00297489 0.134847 +EDGE3 593 642 2.85451 -10.5199 -5.06653 -0.00195246 0.00286662 -0.128595 +EDGE3 594 644 3.56778 -0.00193442 -5.16807 -0.00164859 -0.00690597 0.00343734 +EDGE3 593 644 2.98611 10.5367 -5.27311 0.00803942 0.0013775 0.129092 +EDGE3 594 643 2.84504 -10.5413 -5.05285 0.00480486 -0.0039019 -0.129169 +EDGE3 595 645 3.56049 -0.0137223 -5.17058 0.00742806 0.00836759 -0.00278037 +EDGE3 594 645 2.98565 10.5451 -5.27986 -0.00529153 -0.00198083 0.125056 +EDGE3 595 644 2.85327 -10.5236 -5.07684 0.000308236 0.00497646 -0.124102 +EDGE3 596 646 3.55228 -0.0241371 -5.1826 0.00294394 0.00112561 -0.00177976 +EDGE3 595 646 2.96297 10.5585 -5.28194 -0.00546859 0.00224122 0.119551 +EDGE3 596 645 2.82092 -10.5248 -5.06875 -0.00121963 -0.0040158 -0.122469 +EDGE3 597 647 3.54456 0.0128081 -5.18954 0.00314372 0.00216931 -0.00287284 +EDGE3 596 647 2.97308 10.5614 -5.28403 0.00287946 0.000286137 0.123676 +EDGE3 597 646 2.81467 -10.546 -5.09254 -0.00868927 -0.000585499 -0.121743 +EDGE3 598 648 3.53181 0.00456606 -5.19795 -0.00430959 0.00191029 -0.00119972 +EDGE3 597 648 2.96685 10.5685 -5.28111 -0.00328496 0.0071269 0.129149 +EDGE3 598 647 2.82413 -10.5578 -5.07173 -0.00580296 -0.00185207 -0.128787 +EDGE3 599 649 3.53023 0.0102111 -5.21279 -0.0027712 -0.00115779 -0.00195078 +EDGE3 598 649 2.95715 10.5787 -5.29639 0.00455685 -0.00357852 0.137216 +EDGE3 599 648 2.81091 -10.5866 -5.07752 0.00643665 -0.00970259 -0.130937 +EDGE3 600 650 3.53315 0.00730917 -5.20402 0.00185326 -0.00665992 0.00283373 +EDGE3 599 650 2.9205 10.5812 -5.28899 -0.000541595 0.00114891 0.119214 +EDGE3 600 649 2.78736 -10.5677 -5.08822 0.00471372 0.00123046 -0.123238 +EDGE3 601 651 3.51951 0.026805 -5.19683 0.0081466 -0.00291228 -0.00952172 +EDGE3 600 651 2.9458 10.5874 -5.30364 0.00194616 0.000966582 0.122493 +EDGE3 601 650 2.77931 -10.5793 -5.09956 0.00508244 0.00117906 -0.122995 +EDGE3 602 652 3.53448 0.00934916 -5.20308 -0.00217426 -0.00229758 -0.00584186 +EDGE3 601 652 2.9199 10.5923 -5.3222 0.00556671 -0.00506105 0.126214 +EDGE3 602 651 2.77501 -10.5891 -5.08643 0.000562902 -0.00547223 -0.133159 +EDGE3 603 653 3.51477 -0.012748 -5.22259 0.00700089 0.0020643 0.0037993 +EDGE3 602 653 2.91285 10.6278 -5.32538 -0.00174327 -0.0135517 0.12841 +EDGE3 603 652 2.76831 -10.6056 -5.09984 -0.000865774 0.00604586 -0.128656 +EDGE3 604 654 3.50282 -0.00747928 -5.22427 -0.00882473 -0.00605915 0.000222335 +EDGE3 603 654 2.898 10.614 -5.33382 0.00715097 0.00760289 0.12429 +EDGE3 604 653 2.77937 -10.6081 -5.11801 -0.00740228 0.00599245 -0.125665 +EDGE3 605 655 3.49171 -0.00388981 -5.2173 -0.00750843 9.63905e-05 0.00916696 +EDGE3 604 655 2.90518 10.6276 -5.32749 -0.00653898 0.00383125 0.130683 +EDGE3 605 654 2.75958 -10.6128 -5.12713 0.0115676 0.0106257 -0.130366 +EDGE3 606 656 3.47898 -0.0211428 -5.19835 -0.00170571 0.00134892 0.00382286 +EDGE3 605 656 2.88104 10.6365 -5.31641 -0.00401263 0.000957359 0.132174 +EDGE3 606 655 2.7531 -10.6157 -5.1144 -0.00223818 -2.61333e-05 -0.130014 +EDGE3 607 657 3.47712 -0.000639328 -5.23099 -0.00579484 -0.000226544 0.0017379 +EDGE3 606 657 2.88427 10.6549 -5.32913 0.000793254 0.00307786 0.130432 +EDGE3 607 656 2.73656 -10.6341 -5.11655 0.000898028 0.00242115 -0.131999 +EDGE3 608 658 3.49482 0.0075782 -5.22351 -0.00711598 -0.00152942 0.000646439 +EDGE3 607 658 2.87898 10.6676 -5.33218 0.00263004 -0.00153248 0.129563 +EDGE3 608 657 2.74496 -10.632 -5.12307 0.00687905 0.00450287 -0.131635 +EDGE3 609 659 3.4798 0.0108957 -5.23146 -0.00269386 6.45534e-05 -0.00455512 +EDGE3 608 659 2.87556 10.653 -5.34276 0.00527513 -0.00815719 0.125044 +EDGE3 609 658 2.73576 -10.6473 -5.13657 -0.0019682 0.00249631 -0.12448 +EDGE3 610 660 3.47784 0.00982109 -5.24433 0.00394751 0.00405392 0.00209812 +EDGE3 609 660 2.86139 10.6509 -5.34988 0.00417717 -0.0106181 0.129289 +EDGE3 610 659 2.72598 -10.6538 -5.13463 -0.00658531 0.00496931 -0.128085 +EDGE3 611 661 3.46442 6.94668e-05 -5.23168 0.00811602 0.00401118 -0.004607 +EDGE3 610 661 2.85296 10.6561 -5.35564 -0.00160062 0.00423427 0.121263 +EDGE3 611 660 2.71495 -10.6733 -5.15635 -0.0018777 -0.00747242 -0.12791 +EDGE3 612 662 3.4473 -0.0141399 -5.23931 0.00513964 -0.00244985 0.00357715 +EDGE3 611 662 2.85521 10.676 -5.32186 0.000360537 0.00937129 0.121576 +EDGE3 612 661 2.71588 -10.6798 -5.15405 0.00415164 0.0100265 -0.126221 +EDGE3 613 663 3.44453 0.0123163 -5.24166 0.00190264 0.0152992 0.00127457 +EDGE3 612 663 2.84997 10.6845 -5.34793 -0.00053691 -0.000369167 0.120468 +EDGE3 613 662 2.70449 -10.6861 -5.12622 -0.00354325 -0.0106397 -0.132653 +EDGE3 614 664 3.44726 0.00789725 -5.26035 -0.00131178 -0.00232765 0.00744142 +EDGE3 613 664 2.83618 10.6912 -5.36728 -0.00321286 0.00358921 0.128003 +EDGE3 614 663 2.68705 -10.6998 -5.14392 0.000882297 -0.00225991 -0.133225 +EDGE3 615 665 3.43863 0.00626131 -5.25396 -0.00140698 -0.00827181 -0.00171009 +EDGE3 614 665 2.8414 10.713 -5.37402 0.00134808 -0.00573254 0.130502 +EDGE3 615 664 2.67628 -10.6966 -5.14199 -0.00242538 -0.000707067 -0.134045 +EDGE3 616 666 3.41194 0.00690884 -5.25568 -0.00436937 -0.00239982 0.00254715 +EDGE3 615 666 2.83286 10.7074 -5.3655 0.00731332 -0.00731598 0.121759 +EDGE3 616 665 2.68132 -10.7021 -5.17002 0.000318671 6.03661e-05 -0.125784 +EDGE3 617 667 3.42605 0.000214182 -5.24437 -0.00012013 -0.00922803 -0.00189607 +EDGE3 616 667 2.8018 10.7189 -5.38176 -0.00411574 0.00644514 0.122673 +EDGE3 617 666 2.66572 -10.7153 -5.15112 -0.00386031 0.00279067 -0.130522 +EDGE3 618 668 3.39848 0.010705 -5.29843 0.00110524 -0.00515543 0.00519818 +EDGE3 617 668 2.80146 10.7329 -5.36784 -0.00497484 0.00553968 0.120891 +EDGE3 618 667 2.6737 -10.7281 -5.16945 -0.000752269 -0.00849776 -0.127738 +EDGE3 619 669 3.38646 0.0233382 -5.27848 -0.00521083 -0.00551452 0.00735511 +EDGE3 618 669 2.791 10.7307 -5.39944 -0.00371772 -0.00480861 0.124986 +EDGE3 619 668 2.67752 -10.7359 -5.17111 -2.36674e-05 0.00131565 -0.130293 +EDGE3 620 670 3.39916 0.0181789 -5.26006 -0.00303767 -0.0045622 -0.0051081 +EDGE3 619 670 2.78241 10.7526 -5.39207 -0.00338094 -0.000440483 0.131091 +EDGE3 620 669 2.65666 -10.7373 -5.14719 0.00190323 -0.000854851 -0.129222 +EDGE3 621 671 3.4007 0.0180387 -5.28441 0.0024381 0.00548995 0.000916983 +EDGE3 620 671 2.80104 10.7601 -5.40236 -0.005545 0.00167571 0.12082 +EDGE3 621 670 2.65257 -10.7492 -5.18361 0.00874136 0.0046007 -0.130915 +EDGE3 622 672 3.38853 0.0142383 -5.2987 -4.55248e-05 0.00533208 -0.00341795 +EDGE3 621 672 2.77087 10.7592 -5.39485 0.00135002 -0.00272101 0.133344 +EDGE3 622 671 2.64998 -10.7531 -5.18318 0.00246688 0.000606753 -0.123626 +EDGE3 623 673 3.39023 -0.00551997 -5.29959 0.0147376 0.00877538 0.00455015 +EDGE3 622 673 2.77491 10.7623 -5.41071 0.00257915 -0.00185045 0.135894 +EDGE3 623 672 2.62676 -10.7795 -5.19637 -0.00683169 0.00093575 -0.119619 +EDGE3 624 674 3.37154 0.0161744 -5.30949 0.00374595 -0.00199673 -2.78629e-05 +EDGE3 623 674 2.76896 10.7769 -5.41238 -0.00120939 0.0002927 0.132802 +EDGE3 624 673 2.63096 -10.7877 -5.18565 0.00899243 -0.0104504 -0.122686 +EDGE3 625 675 3.35165 -0.00066222 -5.304 -0.00247299 0.0015913 0.00649492 +EDGE3 624 675 2.76501 10.7993 -5.40933 0.00915562 0.00548342 0.132952 +EDGE3 625 674 2.63075 -10.7906 -5.18133 0.000252692 -0.000673009 -0.128982 +EDGE3 626 676 3.36115 0.0072872 -5.30009 -0.000526752 0.00489191 -2.93153e-05 +EDGE3 625 676 2.74831 10.7846 -5.41047 -0.00616774 0.0144304 0.127462 +EDGE3 626 675 2.61117 -10.7751 -5.20515 -0.00487763 0.00883784 -0.128366 +EDGE3 627 677 3.34783 0.00397299 -5.31958 -0.00605865 -0.000358211 -0.00284394 +EDGE3 626 677 2.75331 10.8133 -5.43379 0.00674238 0.00305624 0.125762 +EDGE3 627 676 2.57924 -10.7901 -5.19208 0.000667297 0.00794027 -0.116553 +EDGE3 628 678 3.33642 -0.006344 -5.32916 -0.00429892 -0.00229212 0.00909879 +EDGE3 627 678 2.72881 10.8134 -5.41384 0.00972272 0.00586277 0.116652 +EDGE3 628 677 2.61158 -10.793 -5.19323 -0.00870985 0.00277971 -0.123209 +EDGE3 629 679 3.34239 0.000577287 -5.3065 0.00278917 0.00152274 -0.000969741 +EDGE3 628 679 2.71771 10.8344 -5.42944 0.000914798 -0.0094227 0.120555 +EDGE3 629 678 2.60426 -10.8106 -5.22656 0.0021237 0.00314506 -0.115391 +EDGE3 630 680 3.32208 -0.000755709 -5.31971 -0.00197466 0.00058688 0.00397953 +EDGE3 629 680 2.72894 10.8306 -5.42636 -0.00124856 0.000510928 0.127111 +EDGE3 630 679 2.59127 -10.8071 -5.21644 -0.0071931 0.00413442 -0.114241 +EDGE3 631 681 3.3159 -0.0179892 -5.32855 -0.00355605 0.00315728 0.0115818 +EDGE3 630 681 2.71292 10.8349 -5.44984 0.00639012 -0.00249686 0.122061 +EDGE3 631 680 2.57635 -10.8247 -5.21745 -0.00489811 0.00548327 -0.122046 +EDGE3 632 682 3.32591 0.00295453 -5.32738 0.00679915 0.00284379 -0.00400042 +EDGE3 631 682 2.7082 10.8701 -5.43363 0.00318026 -3.15211e-06 0.133053 +EDGE3 632 681 2.5682 -10.8285 -5.22237 0.00226009 -0.000689087 -0.121434 +EDGE3 633 683 3.29398 -0.00235708 -5.3296 0.000292255 -0.0077051 -0.00933184 +EDGE3 632 683 2.6961 10.8476 -5.43301 -0.00241474 -0.00519437 0.134988 +EDGE3 633 682 2.59198 -10.8457 -5.2366 -0.00226952 -0.00622913 -0.118553 +EDGE3 634 684 3.32157 0.009226 -5.34063 0.000444925 -0.00911401 0.00664541 +EDGE3 633 684 2.69547 10.8586 -5.44786 0.0020578 0.00159952 0.121664 +EDGE3 634 683 2.55327 -10.8531 -5.23495 0.00106692 0.00291438 -0.129132 +EDGE3 635 685 3.30529 -0.0189795 -5.34069 0.00763387 0.0023016 0.00427264 +EDGE3 634 685 2.69039 10.8664 -5.44562 -0.00616287 -0.00320061 0.119869 +EDGE3 635 684 2.54402 -10.8601 -5.23284 0.00376843 -0.000254647 -0.124777 +EDGE3 636 686 3.27781 -0.000513519 -5.3667 0.00225983 0.006719 -0.00585983 +EDGE3 636 685 2.54082 -10.87 -5.25191 0.00302485 0.00245554 -0.129096 +EDGE3 635 686 2.69046 10.8826 -5.45561 -0.00281402 0.00327323 0.126209 +EDGE3 637 687 3.28501 0.00603132 -5.35105 4.1101e-05 0.00586277 -0.0136012 +EDGE3 637 686 2.53617 -10.8771 -5.24958 0.00345714 -0.00440465 -0.119244 +EDGE3 636 687 2.67178 10.8805 -5.44459 -0.0078509 0.00220673 0.126974 +EDGE3 637 688 2.63917 10.907 -5.45181 0.00488923 -0.00220586 0.12598 +EDGE3 638 688 3.2764 0.00332349 -5.35042 -0.0135902 1.65947e-05 0.00926759 +EDGE3 638 687 2.5331 -10.8767 -5.25482 -0.00854533 -0.0088928 -0.124796 +EDGE3 639 689 3.26458 -0.00159519 -5.35517 0.00238274 -0.00308579 0.00601476 +EDGE3 639 688 2.50988 -10.906 -5.25453 -0.00858395 0.00471177 -0.134369 +EDGE3 638 689 2.65773 10.8818 -5.48716 0.00508704 0.00461288 0.13136 +EDGE3 639 690 2.64176 10.9168 -5.47955 0.00266614 -0.00494338 0.125775 +EDGE3 640 690 3.25376 -0.00387781 -5.3626 -2.73386e-05 -0.0059474 0.00201741 +EDGE3 641 691 3.26023 -0.0166018 -5.35754 0.00725756 -0.00608524 0.00363861 +EDGE3 640 689 2.53086 -10.905 -5.26803 0.000775096 0.00239597 -0.123977 +EDGE3 641 690 2.51609 -10.9107 -5.26096 0.00298331 0.00796982 -0.118696 +EDGE3 640 691 2.63382 10.8983 -5.46978 0.00108546 -0.00393157 0.117085 +EDGE3 641 692 2.64028 10.9223 -5.49508 -0.00465823 0.00538517 0.129215 +EDGE3 642 692 3.24796 -0.0150826 -5.3929 -0.000251645 0.00554776 -0.00409487 +EDGE3 643 693 3.24222 -0.00421274 -5.38471 0.00659945 0.00238907 -0.000350811 +EDGE3 642 691 2.53027 -10.921 -5.27564 0.00199855 0.00980178 -0.126971 +EDGE3 642 693 2.62465 10.9238 -5.48634 -0.00316347 0.00590836 0.127001 +EDGE3 643 692 2.499 -10.9005 -5.24788 0.00432512 -0.000286113 -0.126666 +EDGE3 644 694 3.22579 -0.00880867 -5.38481 -0.00130432 -0.00266242 -0.00133765 +EDGE3 643 694 2.62053 10.9561 -5.47244 0.00281816 0.001772 0.119255 +EDGE3 644 693 2.47373 -10.9627 -5.26468 -0.00180328 0.00326535 -0.124231 +EDGE3 645 695 3.23494 0.00688347 -5.37916 -0.00469572 -0.00273881 -0.00461903 +EDGE3 644 695 2.61432 10.9315 -5.49249 -0.0110731 -0.00130522 0.126446 +EDGE3 646 696 3.22914 0.0100797 -5.39878 0.000170213 0.00472957 -0.00535417 +EDGE3 645 694 2.48342 -10.9275 -5.2676 5.83251e-05 0.00331757 -0.12203 +EDGE3 646 695 2.48391 -10.9527 -5.28231 0.00468282 -0.00517073 -0.1241 +EDGE3 645 696 2.60821 10.9577 -5.50515 -0.00263536 0.00726316 0.12698 +EDGE3 646 697 2.58834 10.9387 -5.49986 -0.00527447 -0.00835079 0.121213 +EDGE3 647 697 3.21551 0.00775847 -5.41701 -0.00176185 0.00205458 0.00142436 +EDGE3 648 698 3.21432 0.00830836 -5.41499 -0.000997305 -0.011419 0.00393356 +EDGE3 647 696 2.48218 -10.9569 -5.29196 -0.00898503 -0.00113199 -0.121513 +EDGE3 648 697 2.43355 -10.9526 -5.30605 0.00222677 0.000673788 -0.128862 +EDGE3 647 698 2.56625 10.9707 -5.49704 0.00645049 0.0029057 0.123801 +EDGE3 648 699 2.58623 10.9569 -5.49772 0.00669391 -0.00109197 0.126131 +EDGE3 649 699 3.22393 0.00661831 -5.40973 0.000404662 0.0057752 -0.00577708 +EDGE3 650 700 3.20569 -0.00429299 -5.40735 0.00192764 0.00672831 0.00500631 +EDGE3 649 698 2.45331 -10.966 -5.28328 0.000354159 0.000714208 -0.124237 +EDGE3 650 699 2.44366 -10.9662 -5.30493 0.00123325 -0.0027734 -0.120474 +EDGE3 649 700 2.58997 10.9794 -5.51129 0.00149298 -0.00284768 0.121625 +EDGE3 650 701 2.57033 10.9944 -5.51443 -0.00379019 0.00668801 0.124518 +EDGE3 651 701 3.19299 -0.0157759 -5.41984 0.0047022 -0.00391507 0.00285424 +EDGE3 652 702 3.20825 -0.00213636 -5.41133 0.00486422 0.00369486 -0.004589 +EDGE3 651 700 2.45165 -11.0043 -5.30874 -0.00632889 0.00122756 -0.124623 +EDGE3 652 701 2.43013 -10.9923 -5.29238 -0.00263025 -0.00023298 -0.129635 +EDGE3 651 702 2.56534 11.002 -5.52501 0.00602545 0.00464385 0.12164 +EDGE3 653 703 3.17071 -0.00587069 -5.40347 -0.00576471 -0.00162808 0.00583512 +EDGE3 652 703 2.55481 11.0145 -5.51907 -0.0079271 -0.00841403 0.114999 +EDGE3 654 704 3.15929 -0.00802741 -5.42712 0.00525602 0.00188731 -0.00166246 +EDGE3 653 702 2.40496 -10.9964 -5.30409 0.00237658 -0.00137453 -0.126564 +EDGE3 654 703 2.38819 -11.0071 -5.32149 0.00716492 -0.00462283 -0.131624 +EDGE3 653 704 2.53863 11.0326 -5.5474 0.00284284 -0.00134417 0.119812 +EDGE3 654 705 2.52882 11.0318 -5.53571 0.00729459 -0.00313775 0.125164 +EDGE3 655 705 3.15273 -0.0146992 -5.42856 -0.00506061 -0.0043957 0.00427792 +EDGE3 656 706 3.16084 0.00389713 -5.44698 -0.00277608 0.0117911 -0.00434843 +EDGE3 655 704 2.41088 -11.0233 -5.31734 0.000208596 -0.00982155 -0.120927 +EDGE3 656 705 2.39445 -11.017 -5.33207 -0.00204425 0.00223939 -0.129471 +EDGE3 655 706 2.5368 11.0449 -5.5499 -0.00558078 0.00972029 0.126253 +EDGE3 656 707 2.51668 11.044 -5.5461 -0.0091897 9.43268e-05 0.127397 +EDGE3 657 707 3.13821 0.00816313 -5.439 0.00610598 0.0016529 0.00678744 +EDGE3 657 706 2.38678 -11.0376 -5.32847 0.00583567 -0.00549897 -0.127423 +EDGE3 658 708 3.14578 0.00148285 -5.42755 -0.00184347 0.00556698 -0.00841119 +EDGE3 658 707 2.37954 -11.0358 -5.34942 -0.0025599 -0.00323134 -0.121728 +EDGE3 657 708 2.51423 11.0573 -5.53897 -0.00129688 0.00596307 0.117204 +EDGE3 659 709 3.14312 -0.00955484 -5.44521 -0.00295373 0.00227585 -0.00452448 +EDGE3 658 709 2.51381 11.0489 -5.54759 0.00754172 -0.00633197 0.11942 +EDGE3 659 708 2.38161 -11.0324 -5.3237 0.000315381 0.00464773 -0.120147 +EDGE3 659 710 2.50843 11.0658 -5.55747 0.00494454 0.00971684 0.125934 +EDGE3 660 710 3.11583 0.0144155 -5.4425 0.001029 -0.00395667 -0.00495863 +EDGE3 661 711 3.12809 -0.0103671 -5.4447 0.00141253 -0.00289323 0.00553146 +EDGE3 660 709 2.39044 -11.0562 -5.33431 -0.005222 0.00748247 -0.122049 +EDGE3 661 710 2.38111 -11.0449 -5.3614 0.00177127 -0.00848762 -0.127398 +EDGE3 660 711 2.49839 11.0547 -5.55562 0.00453506 0.00858348 0.121176 +EDGE3 662 712 3.11083 0.00658058 -5.46349 -0.00891125 -0.000299279 -0.00703956 +EDGE3 661 712 2.49504 11.0741 -5.58131 0.00377718 -0.00471976 0.126865 +EDGE3 662 711 2.35615 -11.0921 -5.35217 -0.00217872 -0.00928728 -0.116502 +EDGE3 662 713 2.49147 11.0772 -5.57359 -0.000511252 -0.00181774 0.126867 +EDGE3 663 713 3.08862 0.010631 -5.4421 -0.00597536 0.00355305 -0.00680103 +EDGE3 664 714 3.10514 -0.0075908 -5.46575 -0.000280252 0.00490649 -0.0134259 +EDGE3 663 712 2.34767 -11.0576 -5.35955 -0.004612 -0.00658689 -0.13266 +EDGE3 664 713 2.34626 -11.0743 -5.33912 0.00380304 -0.00586309 -0.133888 +EDGE3 663 714 2.47419 11.079 -5.58272 -0.00773182 -0.00750751 0.125645 +EDGE3 664 715 2.46856 11.0913 -5.57066 -0.00192344 0.00105709 0.129348 +EDGE3 665 715 3.09398 0.00488262 -5.48468 0.00401377 0.00325879 0.00516225 +EDGE3 666 716 3.07798 0.00438289 -5.47519 0.0090196 0.00272414 -0.00303572 +EDGE3 665 714 2.34135 -11.0794 -5.34404 -0.000982328 -0.00743289 -0.129982 +EDGE3 666 715 2.3268 -11.1009 -5.36314 0.00636603 0.00357994 -0.133066 +EDGE3 665 716 2.4543 11.0844 -5.56877 0.00358031 -0.00340148 0.11997 +EDGE3 667 717 3.07592 -0.00254398 -5.47109 0.00467366 -0.00660649 0.000322891 +EDGE3 666 717 2.44914 11.1054 -5.58426 -0.0026971 -0.00546378 0.13086 +EDGE3 668 718 3.08916 0.00706369 -5.47864 -0.00562518 -0.00912327 0.00422307 +EDGE3 667 716 2.3258 -11.1002 -5.38653 -0.0102063 -0.00117528 -0.130672 +EDGE3 668 717 2.29885 -11.1077 -5.35546 -0.0106815 0.00309349 -0.129889 +EDGE3 667 718 2.42405 11.1047 -5.58576 0.00457738 -0.00313889 0.126132 +EDGE3 668 719 2.4302 11.1215 -5.59696 -0.00128603 -0.00622139 0.129004 +EDGE3 669 719 3.07379 0.0237102 -5.4745 0.000591618 0.00386754 -0.00115179 +EDGE3 670 720 3.05795 0.0117416 -5.48082 0.00408836 0.0036976 0.00360537 +EDGE3 669 718 2.31253 -11.1136 -5.3578 -0.0131862 -0.00990467 -0.119853 +EDGE3 670 719 2.31148 -11.1141 -5.40229 -0.00561444 0.00154231 -0.132376 +EDGE3 669 720 2.4403 11.1273 -5.57916 0.00576095 0.000239963 0.135489 +EDGE3 670 721 2.43141 11.1269 -5.58453 0.0156876 -0.0037319 0.124935 +EDGE3 671 721 3.06038 -0.0035533 -5.49059 0.00111122 0.00538531 0.00471228 +EDGE3 671 720 2.28635 -11.1227 -5.36052 0.00214029 -0.00156001 -0.137636 +EDGE3 672 722 3.05844 -0.00216468 -5.50266 0.000577424 -0.00616314 -0.00069187 +EDGE3 671 722 2.41468 11.1268 -5.62655 0.00597954 0.0105475 0.125748 +EDGE3 672 721 2.28988 -11.1448 -5.3873 0.00324249 0.0137619 -0.122546 +EDGE3 673 723 3.0359 0.00602202 -5.50746 0.00399703 -0.00247079 0.002523 +EDGE3 672 723 2.39423 11.1717 -5.63687 -0.00135727 0.00129664 0.126193 +EDGE3 673 722 2.28743 -11.155 -5.37664 -0.00533869 0.00217378 -0.133718 +EDGE3 674 724 3.02532 0.0132361 -5.50522 -0.00213546 -0.00519174 -0.00224275 +EDGE3 673 724 2.40157 11.1544 -5.62834 0.00802757 -0.00217302 0.117051 +EDGE3 674 723 2.29482 -11.1553 -5.40531 0.00160019 0.0114978 -0.11736 +EDGE3 675 725 3.02078 -0.00792746 -5.52225 -0.00346226 -0.00265901 0.00521949 +EDGE3 674 725 2.37833 11.1603 -5.60666 5.18617e-05 -0.0037949 0.12918 +EDGE3 675 724 2.2688 -11.1563 -5.40342 -0.00591174 0.000364811 -0.121622 +EDGE3 676 726 2.994 0.00824623 -5.50171 -0.00231833 -0.000457719 -0.00394966 +EDGE3 675 726 2.36881 11.1733 -5.62831 -0.0091388 0.00279924 0.130107 +EDGE3 676 725 2.24792 -11.1676 -5.38335 0.00134399 -0.00234803 -0.132375 +EDGE3 677 727 3.01569 0.00253266 -5.54076 0.0102567 -0.0010397 0.00266533 +EDGE3 676 727 2.38688 11.1692 -5.63993 0.00868037 -0.00483925 0.125338 +EDGE3 677 726 2.2568 -11.1786 -5.40194 -0.00297512 0.00615843 -0.119175 +EDGE3 678 728 3.00446 -0.00765036 -5.50831 0.00122777 -0.00557978 -0.00217663 +EDGE3 677 728 2.35998 11.2054 -5.64368 -0.001711 0.00442207 0.126051 +EDGE3 678 727 2.26917 -11.1622 -5.40576 -0.00852762 -0.00716694 -0.125686 +EDGE3 679 729 2.9875 -0.0049591 -5.51862 -0.00205546 -0.00770817 -0.00172245 +EDGE3 678 729 2.37287 11.2037 -5.6128 0.000170173 0.00651936 0.117198 +EDGE3 679 728 2.22451 -11.1748 -5.4036 -0.00384138 -0.000196333 -0.122723 +EDGE3 680 730 3.00293 0.00763425 -5.52026 0.00438006 0.00126942 0.000888038 +EDGE3 679 730 2.35394 11.1942 -5.62644 0.00276113 -0.00569452 0.127404 +EDGE3 680 729 2.23338 -11.1943 -5.42943 0.00356039 -0.00334336 -0.120332 +EDGE3 681 731 2.98843 -0.00235014 -5.54082 -0.0027869 -0.00125951 -0.00437472 +EDGE3 680 731 2.33204 11.2073 -5.63171 0.00158909 0.00498643 0.128738 +EDGE3 681 730 2.22103 -11.1907 -5.42574 0.00106119 0.00828243 -0.123615 +EDGE3 682 732 2.9776 0.00165386 -5.53456 0.00309813 0.00786635 -0.00888145 +EDGE3 681 732 2.32308 11.2238 -5.62656 0.00410007 -0.00545216 0.116981 +EDGE3 682 731 2.24785 -11.2136 -5.43082 0.00165819 0.00210324 -0.129606 +EDGE3 683 733 2.98965 0.0200035 -5.54347 0.00512376 0.00474693 0.0013732 +EDGE3 682 733 2.35322 11.2347 -5.65424 0.00128888 0.00491638 0.120813 +EDGE3 683 732 2.21359 -11.2149 -5.43719 0.00120678 0.0025902 -0.131407 +EDGE3 684 734 2.96963 0.00699067 -5.5479 -0.00173777 0.00568274 0.00286206 +EDGE3 683 734 2.32686 11.2336 -5.65636 -0.00956511 0.0037211 0.121875 +EDGE3 684 733 2.20817 -11.213 -5.39511 0.007339 -0.000193578 -0.119257 +EDGE3 685 735 2.95321 0.00421967 -5.54895 -0.00416884 0.0028691 -0.0022224 +EDGE3 684 735 2.31319 11.2564 -5.65269 0.00491452 0.00111927 0.126419 +EDGE3 685 734 2.19056 -11.248 -5.42678 -0.00102958 -0.00470655 -0.122253 +EDGE3 686 736 2.96482 -0.00659202 -5.57297 -0.00507627 0.00831641 -0.00171944 +EDGE3 685 736 2.29667 11.2584 -5.66916 -0.00635889 -0.0014494 0.11794 +EDGE3 686 735 2.18993 -11.2132 -5.43913 0.00326963 -0.000525273 -0.131249 +EDGE3 687 737 2.93276 -0.00532779 -5.54371 0.00483125 0.00366904 0.00232911 +EDGE3 686 737 2.27675 11.2622 -5.6589 0.00100898 -1.75989e-05 0.131458 +EDGE3 687 736 2.19805 -11.2443 -5.44417 -0.00103232 -0.00325488 -0.116316 +EDGE3 688 738 2.95257 0.0128689 -5.55923 -0.00797728 0.0063751 -0.00183378 +EDGE3 687 738 2.29753 11.276 -5.65956 -0.00515751 -0.00301004 0.120118 +EDGE3 688 737 2.18103 -11.2475 -5.43451 0.00691902 0.00274696 -0.129386 +EDGE3 689 739 2.92845 0.00265626 -5.56091 -0.00261743 0.0041004 0.00909401 +EDGE3 688 739 2.27504 11.2733 -5.65863 0.00244345 -0.000418402 0.125925 +EDGE3 689 738 2.17784 -11.2665 -5.43881 0.00643306 -0.00495825 -0.124137 +EDGE3 690 740 2.94249 -0.0142831 -5.56405 -0.00023124 0.00150793 -0.00257882 +EDGE3 689 740 2.25914 11.2726 -5.66925 3.32978e-05 -0.000875355 0.127827 +EDGE3 690 739 2.16646 -11.2592 -5.44626 -0.0089866 -0.00098245 -0.118203 +EDGE3 691 741 2.91114 -0.0180938 -5.55357 -0.00424722 -0.00257671 0.00860215 +EDGE3 690 741 2.26746 11.2763 -5.67132 -0.014013 0.00104214 0.118603 +EDGE3 691 740 2.1567 -11.2836 -5.45196 0.00626197 0.00193463 -0.131205 +EDGE3 692 742 2.90879 -0.0105658 -5.5675 -0.00421916 -0.00172595 0.00610005 +EDGE3 691 742 2.26378 11.2825 -5.69722 0.000210173 0.00304373 0.125295 +EDGE3 692 741 2.12923 -11.2671 -5.4593 -0.00755896 0.00373156 -0.124462 +EDGE3 693 743 2.90422 -0.00231427 -5.575 0.00218117 0.00104663 -0.00136966 +EDGE3 692 743 2.25324 11.2777 -5.65914 0.0028874 0.0131369 0.128127 +EDGE3 693 742 2.13268 -11.2833 -5.43387 0.00598244 -0.000317965 -0.12179 +EDGE3 694 744 2.87574 -0.0115949 -5.582 -0.00170586 -0.00311926 -0.005256 +EDGE3 693 744 2.24289 11.2856 -5.68171 0.00731741 -0.00063642 0.124988 +EDGE3 694 743 2.11848 -11.2895 -5.43337 0.000315774 -0.00822463 -0.121107 +EDGE3 695 745 2.90452 -0.0224957 -5.57004 6.54399e-05 -0.00340535 0.00434976 +EDGE3 694 745 2.22265 11.311 -5.69151 -0.00253968 -0.0044063 0.121727 +EDGE3 695 744 2.10876 -11.3105 -5.45575 0.00088396 0.00399071 -0.128631 +EDGE3 696 746 2.86505 -0.00916533 -5.5735 -0.00032092 -0.00116057 0.00122672 +EDGE3 695 746 2.21958 11.321 -5.68753 0.00247744 -0.0107087 0.127023 +EDGE3 696 745 2.10751 -11.3106 -5.47337 0.000490654 -0.00491303 -0.132888 +EDGE3 697 747 2.87425 0.00492534 -5.59872 -0.00248637 -0.00389203 -0.0039998 +EDGE3 696 747 2.21228 11.3194 -5.69489 0.00054545 0.00591152 0.124856 +EDGE3 697 746 2.10794 -11.3167 -5.46507 -0.00283587 -0.00697077 -0.125717 +EDGE3 698 748 2.86565 8.08475e-05 -5.59093 -0.00187278 -0.00491143 0.00103075 +EDGE3 697 748 2.20104 11.3178 -5.70462 -0.00416272 0.00138265 0.123878 +EDGE3 698 747 2.10937 -11.3234 -5.49155 -0.0109064 0.00490727 -0.127763 +EDGE3 699 749 2.87229 -0.00351402 -5.60296 -2.0995e-05 0.00477961 -0.00503376 +EDGE3 698 749 2.18228 11.3197 -5.71393 -0.000283003 8.44992e-05 0.11797 +EDGE3 699 748 2.10169 -11.3229 -5.46985 -0.00619267 -0.0111943 -0.131747 +EDGE3 700 750 2.85275 -0.00384588 -5.60746 0.00719871 -0.00607033 -0.0110539 +EDGE3 699 750 2.19314 11.3597 -5.72041 0.00388018 0.00346099 0.120614 +EDGE3 700 749 2.08565 -11.3317 -5.46393 0.0006382 -0.00263004 -0.125999 +EDGE3 701 751 2.84365 0.00273466 -5.60367 -0.0037816 -0.00171522 0.00987049 +EDGE3 700 751 2.2044 11.3496 -5.71008 0.00391959 0.00687841 0.126338 +EDGE3 701 750 2.0673 -11.3353 -5.49287 0.000963603 -0.000349693 -0.129806 +EDGE3 702 752 2.82946 0.0198147 -5.59751 -0.00939747 0.00282579 0.000976887 +EDGE3 701 752 2.17925 11.3527 -5.71894 0.00478148 -0.00489951 0.122937 +EDGE3 702 751 2.08393 -11.3371 -5.48959 -3.94029e-05 3.52847e-05 -0.132811 +EDGE3 703 753 2.84511 -0.0137373 -5.61442 0.00446996 0.00237982 -0.00348336 +EDGE3 702 753 2.16326 11.3719 -5.70593 0.0041021 -0.000435272 0.121096 +EDGE3 703 752 2.04356 -11.3509 -5.48643 0.00174764 0.00341677 -0.129154 +EDGE3 704 754 2.81449 -0.0054251 -5.61251 -0.00410529 0.00666579 0.00321477 +EDGE3 703 754 2.17976 11.3506 -5.7232 -0.00689582 0.00650081 0.123331 +EDGE3 704 753 2.06415 -11.3579 -5.48859 0.00489778 -0.00523539 -0.125073 +EDGE3 705 755 2.81622 -0.00705598 -5.6232 -0.00151222 0.00144958 0.00137241 +EDGE3 704 755 2.16485 11.3682 -5.70808 -0.00158727 -0.00439418 0.125563 +EDGE3 705 754 2.03742 -11.3663 -5.48931 -0.00442153 -0.00596838 -0.13015 +EDGE3 706 756 2.8034 0.01105 -5.62965 0.0023295 -0.00258073 -0.00102984 +EDGE3 705 756 2.1469 11.3823 -5.72028 -0.00486448 -0.00441162 0.127917 +EDGE3 706 755 2.03634 -11.4015 -5.50421 -0.0106169 -0.0120838 -0.121422 +EDGE3 707 757 2.80274 -0.00296326 -5.62609 -0.00297874 0.00128047 0.00184436 +EDGE3 706 757 2.1482 11.3842 -5.72574 -0.00345893 -0.003669 0.125474 +EDGE3 707 756 2.04378 -11.389 -5.52804 0.00103698 -0.00289384 -0.118273 +EDGE3 708 758 2.76882 -0.00111354 -5.6291 -0.00572772 0.00387281 0.00218804 +EDGE3 707 758 2.13146 11.4014 -5.74856 -0.00461305 0.00451214 0.134671 +EDGE3 708 757 2.01599 -11.3867 -5.50267 0.00280224 0.0023058 -0.116994 +EDGE3 709 759 2.80165 0.00400825 -5.62643 0.0060565 -0.000339151 -0.0014062 +EDGE3 708 759 2.12782 11.4055 -5.73449 -0.003148 0.00753463 0.11764 +EDGE3 709 758 2.03011 -11.3933 -5.51832 0.00265261 -0.00589279 -0.140204 +EDGE3 710 760 2.78892 -0.0235017 -5.61263 0.0063813 0.00762754 -0.00849109 +EDGE3 709 760 2.11512 11.4227 -5.75436 -0.00534348 -0.00607981 0.127956 +EDGE3 710 759 2.01813 -11.4086 -5.51061 0.00990668 -0.0042833 -0.123877 +EDGE3 711 761 2.77228 -0.0116383 -5.64291 -0.00446313 -0.00205222 0.00173194 +EDGE3 710 761 2.11802 11.4088 -5.74149 -0.00582033 -0.00121501 0.119393 +EDGE3 711 760 2.00709 -11.4002 -5.50917 0.00403486 0.00190605 -0.124833 +EDGE3 712 762 2.76989 -0.00377797 -5.63554 0.00566134 0.00540246 -0.00196133 +EDGE3 711 762 2.11267 11.4072 -5.75133 -0.00418655 -0.00499411 0.11713 +EDGE3 712 761 1.97588 -11.4056 -5.52034 -0.00111519 -0.00542833 -0.122155 +EDGE3 713 763 2.76527 -0.00479498 -5.66084 -0.00356252 -4.77328e-05 0.00278872 +EDGE3 712 763 2.09328 11.4207 -5.77525 0.007542 0.00205616 0.117251 +EDGE3 713 762 1.99216 -11.4227 -5.54014 -0.00600098 -0.0128276 -0.12655 +EDGE3 714 764 2.74373 0.0019611 -5.63803 0.00206666 0.00504587 0.00267917 +EDGE3 713 764 2.10218 11.4239 -5.76242 0.00418478 0.00151255 0.11858 +EDGE3 714 763 1.97548 -11.4251 -5.51834 -0.00025938 0.00093812 -0.123283 +EDGE3 715 765 2.7509 -0.00281 -5.63559 -0.00242977 -0.00338711 -0.00441875 +EDGE3 714 765 2.09333 11.4354 -5.75497 -0.00714783 0.00314786 0.129926 +EDGE3 715 764 1.97861 -11.4388 -5.52793 0.00218536 -0.00281737 -0.129652 +EDGE3 716 766 2.72761 -0.0124774 -5.65805 -0.00475766 0.00228341 0.00304106 +EDGE3 715 766 2.07668 11.4625 -5.77122 0.00681256 -0.00132129 0.132441 +EDGE3 716 765 1.97262 -11.4404 -5.51673 -0.00561529 0.00270999 -0.132025 +EDGE3 717 767 2.72915 0.026128 -5.664 0.00310353 0.00141434 -0.000343185 +EDGE3 716 767 2.06037 11.4625 -5.76735 0.00100364 0.00350328 0.120891 +EDGE3 717 766 1.95338 -11.4658 -5.53602 0.00748284 0.00673228 -0.123935 +EDGE3 718 768 2.71881 -0.0211844 -5.67176 -0.00123089 -0.00442538 -0.00365814 +EDGE3 717 768 2.04365 11.4539 -5.77352 0.00198783 -0.00100989 0.124324 +EDGE3 718 767 1.93871 -11.4501 -5.55198 -0.00252834 0.000636146 -0.124059 +EDGE3 719 769 2.72018 -0.00921075 -5.67929 0.000967367 0.00378405 0.00157509 +EDGE3 718 769 2.0489 11.4789 -5.77199 -0.000258614 -0.00239432 0.12991 +EDGE3 719 768 1.95345 -11.46 -5.54621 0.000114627 0.00146812 -0.125769 +EDGE3 720 770 2.7045 -0.00145254 -5.67081 0.0095351 -0.00404065 -0.00467624 +EDGE3 719 770 2.03698 11.48 -5.77775 -0.00689224 -0.00136032 0.132838 +EDGE3 720 769 1.93315 -11.4465 -5.5455 -4.4509e-05 -0.000970695 -0.119755 +EDGE3 721 771 2.7228 0.000695874 -5.65866 -0.00214024 0.0055149 -0.00631783 +EDGE3 720 771 2.03111 11.4642 -5.78881 0.000546242 0.00648078 0.124383 +EDGE3 721 770 1.92848 -11.467 -5.55857 -0.00426814 0.00585794 -0.128188 +EDGE3 722 772 2.68051 0.000939971 -5.66726 0.00606725 0.00625356 -0.00301353 +EDGE3 721 772 2.03941 11.4754 -5.79796 -0.00669062 -0.00212535 0.123437 +EDGE3 722 771 1.92999 -11.4787 -5.56095 0.00511097 -0.00205956 -0.118413 +EDGE3 723 773 2.69724 0.00168702 -5.68681 0.00429671 0.0057651 -0.00547096 +EDGE3 722 773 2.01728 11.4724 -5.80305 0.00137948 -0.00253772 0.117738 +EDGE3 723 772 1.91755 -11.5004 -5.56645 -0.00149826 -0.00234864 -0.116526 +EDGE3 724 774 2.68359 -0.0164968 -5.68219 -0.00568802 0.00026885 0.00406809 +EDGE3 723 774 2.01868 11.486 -5.77823 -0.0111716 -0.00206641 0.125421 +EDGE3 725 775 2.68445 -0.00314103 -5.68342 0.00105683 -0.00516397 0.00461788 +EDGE3 724 773 1.90758 -11.5063 -5.5536 0.0021998 -0.0015994 -0.119809 +EDGE3 725 774 1.88604 -11.5077 -5.56678 0.00486602 0.00436772 -0.118757 +EDGE3 724 775 2.0145 11.5045 -5.79197 -0.00636481 0.00333455 0.126655 +EDGE3 725 776 2.00046 11.5155 -5.79281 -0.00276776 0.00526781 0.125126 +EDGE3 726 776 2.67248 -0.0113522 -5.6799 -0.0027347 0.00775743 0.00535381 +EDGE3 727 777 2.66338 0.00271755 -5.66664 0.00262552 0.00121644 0.00285352 +EDGE3 726 775 1.89146 -11.4995 -5.58232 -0.000503255 0.00535226 -0.13189 +EDGE3 727 776 1.88597 -11.5066 -5.56761 0.00739138 -0.00429675 -0.123765 +EDGE3 726 777 1.99101 11.5268 -5.80066 0.00356539 0.00142404 0.120931 +EDGE3 727 778 1.99038 11.539 -5.81819 -0.00371 -0.0047736 0.124123 +EDGE3 728 778 2.65402 0.0173175 -5.68548 0.000362213 -0.00253853 -0.00306661 +EDGE3 728 777 1.86905 -11.5231 -5.5755 -0.000522001 -0.00307991 -0.118588 +EDGE3 729 779 2.64931 0.0106759 -5.69156 0.00119036 -0.00323312 -0.00257743 +EDGE3 729 778 1.87666 -11.5316 -5.58209 -0.000999236 -0.00354125 -0.123423 +EDGE3 728 779 1.99872 11.551 -5.81239 -0.00652777 0.00245745 0.121878 +EDGE3 730 780 2.62605 -0.00257988 -5.69938 -0.00924701 -0.00818741 -0.00183031 +EDGE3 729 780 1.96924 11.5497 -5.82751 -0.00350915 -0.00305181 0.131119 +EDGE3 730 779 1.87221 -11.5141 -5.5831 -0.00293569 -0.00187604 -0.122577 +EDGE3 731 781 2.63344 -0.0145517 -5.70934 0.000722254 -0.00522924 -0.00460473 +EDGE3 730 781 1.96787 11.5449 -5.82076 -0.00304083 0.00407595 0.13284 +EDGE3 731 780 1.83632 -11.548 -5.58229 0.0039264 -8.16437e-05 -0.127068 +EDGE3 731 782 1.96463 11.5506 -5.83325 -0.00452691 -0.00466957 0.125905 +EDGE3 732 782 2.61985 -0.0124523 -5.69786 -0.00180619 0.00923827 0.00349675 +EDGE3 733 783 2.62485 0.0070233 -5.70063 0.00508283 -0.00206436 -0.00818665 +EDGE3 732 781 1.85226 -11.5258 -5.58773 -0.00186037 0.00242378 -0.115973 +EDGE3 733 782 1.85451 -11.5486 -5.60359 0.00774103 -0.00393741 -0.125985 +EDGE3 732 783 1.92419 11.5484 -5.82315 0.00157489 -0.00645487 0.123332 +EDGE3 734 784 2.60765 0.000596309 -5.70878 0.0068294 -0.00529719 -0.000291515 +EDGE3 733 784 1.95179 11.5549 -5.82799 0.00705561 0.00581374 0.130116 +EDGE3 734 783 1.8409 -11.5506 -5.5937 0.00461831 0.00237386 -0.119618 +EDGE3 734 785 1.9431 11.5612 -5.82746 0.00486872 -0.00654993 0.124986 +EDGE3 735 785 2.6053 -0.00536876 -5.72914 0.00661358 0.0067684 -0.00134062 +EDGE3 736 786 2.59212 -0.000516151 -5.71996 -0.00782652 0.00285417 0.00633123 +EDGE3 735 784 1.82293 -11.5657 -5.59463 0.00131161 -0.00496211 -0.121715 +EDGE3 735 786 1.90386 11.5849 -5.84312 0.0031598 -0.000381679 0.125007 +EDGE3 736 785 1.81328 -11.5628 -5.59317 0.00138586 -0.00581601 -0.124434 +EDGE3 736 787 1.90479 11.5771 -5.86588 -0.00366903 0.00385023 0.126084 +EDGE3 737 787 2.58232 -0.0256925 -5.71286 0.0116319 0.000707341 0.000812141 +EDGE3 738 788 2.56203 0.0134205 -5.73991 -0.00911915 -0.00361785 0.00133391 +EDGE3 737 786 1.82882 -11.5707 -5.63008 0.00162746 0.00461138 -0.122502 +EDGE3 738 787 1.80238 -11.5697 -5.63718 0.00514571 -0.00532388 -0.130035 +EDGE3 737 788 1.89681 11.5794 -5.85569 -0.00893866 -0.00572029 0.126288 +EDGE3 738 789 1.89962 11.5824 -5.84818 -0.00563718 0.00534526 0.126007 +EDGE3 739 789 2.5643 0.0165219 -5.75012 -0.00264367 0.00496268 -0.00118027 +EDGE3 740 790 2.56869 -0.0103541 -5.74119 0.0051391 0.000385615 -0.00490763 +EDGE3 739 788 1.78738 -11.578 -5.62594 -0.000393354 0.000408293 -0.12307 +EDGE3 740 789 1.79813 -11.589 -5.61904 0.00193426 0.00530097 -0.131742 +EDGE3 739 790 1.87956 11.6012 -5.84919 -0.00290183 0.0118061 0.119435 +EDGE3 740 791 1.88945 11.6007 -5.83403 0.00142107 -0.00282246 0.118036 +EDGE3 741 791 2.56138 0.00547732 -5.73379 0.0130413 0.00482474 -0.00114944 +EDGE3 742 792 2.55107 -0.000904931 -5.7373 -0.0015475 0.00489067 0.0134115 +EDGE3 741 790 1.78306 -11.5859 -5.63754 -0.000276105 0.00308992 -0.134497 +EDGE3 742 791 1.78512 -11.5921 -5.63091 -0.00556308 0.00556985 -0.125023 +EDGE3 741 792 1.89241 11.6256 -5.84628 -0.000329146 -0.000822643 0.122313 +EDGE3 743 793 2.52561 -0.00279006 -5.7416 -0.00523876 -0.00189339 -0.00410228 +EDGE3 742 793 1.85579 11.6199 -5.8604 -0.00291 -0.00504965 0.11525 +EDGE3 743 792 1.7501 -11.6108 -5.61658 -0.000975666 -0.00520135 -0.13059 +EDGE3 744 794 2.5163 -0.00704287 -5.74526 0.000380781 -0.000539547 -0.00560682 +EDGE3 743 794 1.86351 11.6229 -5.88632 -0.00963708 -0.00347372 0.125889 +EDGE3 745 795 2.53468 -0.0104163 -5.75097 -0.00989428 0.00282234 0.000720028 +EDGE3 744 793 1.77172 -11.6016 -5.62802 0.00970272 0.000289515 -0.125223 +EDGE3 745 794 1.75212 -11.6228 -5.63451 -0.000722702 -0.00599737 -0.1297 +EDGE3 744 795 1.86527 11.6144 -5.86555 -0.00684233 0.00338161 0.130549 +EDGE3 746 796 2.51136 0.00870336 -5.72249 0.00739381 -0.000693711 -0.00545614 +EDGE3 745 796 1.86854 11.6194 -5.87342 -0.0043212 0.00671362 0.119635 +EDGE3 746 795 1.74925 -11.6035 -5.64224 0.00351454 -0.00489505 -0.121463 +EDGE3 746 797 1.84768 11.6259 -5.8704 0.000845793 -0.00500953 0.130844 +EDGE3 747 797 2.52806 0.00744564 -5.74602 0.00293126 0.0048215 -0.000991763 +EDGE3 748 798 2.51387 -0.0178833 -5.7639 0.0086968 -0.00847308 0.0037842 +EDGE3 747 796 1.74211 -11.6261 -5.63932 -0.00455708 0.00399416 -0.122291 +EDGE3 748 797 1.72076 -11.6428 -5.63673 0.000149974 0.00465535 -0.123347 +EDGE3 747 798 1.81654 11.6561 -5.87095 -0.0022793 -0.00193789 0.11506 +EDGE3 748 799 1.81953 11.6429 -5.87301 0.00131083 0.00534328 0.132611 +EDGE3 749 799 2.4802 -0.0061336 -5.74931 -0.00607472 0.00205175 -0.0028734 +EDGE3 750 800 2.49862 0.0082638 -5.77072 0.00230316 -0.001735 -0.00240446 +EDGE3 749 798 1.73161 -11.6356 -5.66029 0.00193124 0.00489205 -0.125621 +EDGE3 750 799 1.72727 -11.6519 -5.6468 -0.0054363 0.00474412 -0.134944 +EDGE3 749 800 1.80823 11.6556 -5.87524 0.00183726 0.00870731 0.117615 +EDGE3 751 801 2.49096 -0.00354145 -5.7555 0.000129719 -0.00395419 -0.00171529 +EDGE3 750 801 1.80384 11.664 -5.89005 0.00284636 -0.00042959 0.132132 +EDGE3 751 800 1.69059 -11.6497 -5.64752 -0.00279109 -0.00310102 -0.130229 +EDGE3 751 802 1.79739 11.6507 -5.88074 -0.00390298 0.0050827 0.129565 +EDGE3 752 802 2.4759 -0.00654326 -5.78171 0.00356024 0.00998617 -0.000839141 +EDGE3 753 803 2.4787 0.00300082 -5.76343 -0.000199942 0.00345704 0.00902867 +EDGE3 752 801 1.69091 -11.6627 -5.65369 0.000268323 -0.00125702 -0.123309 +EDGE3 753 802 1.68065 -11.6803 -5.65595 0.000322267 0.00530471 -0.132229 +EDGE3 752 803 1.78358 11.6683 -5.90323 0.00466553 0.00247576 0.117638 +EDGE3 754 804 2.45534 0.00800497 -5.78022 -0.000124856 -0.0057662 0.000244834 +EDGE3 753 804 1.78464 11.6767 -5.88712 -0.00744982 0.00152889 0.125736 +EDGE3 754 803 1.69021 -11.6646 -5.65845 -0.00216919 0.0118496 -0.130025 +EDGE3 754 805 1.77845 11.681 -5.91046 0.00291214 0.00427228 0.113822 +EDGE3 755 805 2.45615 0.00633166 -5.77695 0.000835518 -0.0034207 -0.0110422 +EDGE3 755 804 1.66936 -11.6715 -5.66269 -0.00524181 -0.0127454 -0.116598 +EDGE3 756 806 2.44934 0.00836975 -5.78497 -0.00946834 -0.00244703 0.000916183 +EDGE3 755 806 1.74502 11.7046 -5.86887 -0.00073445 0.0105035 0.127909 +EDGE3 757 807 2.44399 0.000240831 -5.78337 0.00129701 0.00144546 -0.000350348 +EDGE3 756 805 1.65743 -11.6808 -5.6681 -0.00348338 0.00435933 -0.12133 +EDGE3 756 807 1.73896 11.6844 -5.89306 0.00577459 -0.00800321 0.12623 +EDGE3 757 806 1.67804 -11.6882 -5.68882 -0.00221858 -0.00346605 -0.122817 +EDGE3 758 808 2.43747 0.00902785 -5.78921 -0.00211969 -0.00181356 -0.00162664 +EDGE3 757 808 1.72416 11.6766 -5.90429 0.00247557 0.00046096 0.127453 +EDGE3 758 807 1.64935 -11.6856 -5.68296 -0.000876679 0.00296847 -0.123485 +EDGE3 758 809 1.75314 11.7047 -5.9245 0.00617195 -0.00593301 0.131271 +EDGE3 759 809 2.43705 -0.00862636 -5.79463 0.00741967 0.00402201 0.0029681 +EDGE3 760 810 2.41392 -0.00229971 -5.79542 -0.00898301 0.00483592 0.00410863 +EDGE3 759 808 1.64466 -11.7033 -5.6771 -0.000242572 -0.000125987 -0.127185 +EDGE3 760 809 1.63919 -11.6914 -5.67435 0.00367696 -0.00611354 -0.127191 +EDGE3 759 810 1.73948 11.7132 -5.91191 0.00587463 0.00410486 0.128249 +EDGE3 761 811 2.41412 0.00130129 -5.80926 -0.00175173 -0.00168737 -0.00105234 +EDGE3 760 811 1.72891 11.7122 -5.91129 0.010596 -0.00574336 0.129543 +EDGE3 761 810 1.62887 -11.7126 -5.68122 0.000132319 0.0019321 -0.120786 +EDGE3 762 812 2.40971 -0.00524921 -5.7865 0.0017257 -0.000489674 -0.00657978 +EDGE3 762 811 1.60418 -11.7334 -5.6602 -0.00316692 0.00365396 -0.127599 +EDGE3 761 812 1.70537 11.7194 -5.91306 -0.00980028 0.00459687 0.12939 +EDGE3 763 813 2.40534 -0.000829876 -5.81883 -0.00552753 0.00687605 0.00318518 +EDGE3 762 813 1.72375 11.7274 -5.92011 0.00415107 0.00713312 0.123581 +EDGE3 763 812 1.62685 -11.7338 -5.68579 0.0100415 -0.000135465 -0.131719 +EDGE3 764 814 2.39077 -0.00882328 -5.80077 -0.00267523 0.00237168 -0.000538015 +EDGE3 763 814 1.69835 11.7201 -5.90806 -0.000536347 0.00300922 0.131492 +EDGE3 764 813 1.61551 -11.7268 -5.68324 -0.00316522 -0.00459767 -0.121064 +EDGE3 765 815 2.39047 0.00368618 -5.81495 0.00141319 -0.00838279 -0.00422081 +EDGE3 764 815 1.66784 11.7445 -5.93434 0.00973396 0.00131217 0.129051 +EDGE3 765 814 1.60004 -11.7274 -5.70305 0.00819532 -0.000934952 -0.129862 +EDGE3 766 816 2.37961 -0.00977852 -5.82193 0.00534495 0.000499097 -0.00597449 +EDGE3 765 816 1.68203 11.7389 -5.92257 0.00298038 -0.00271931 0.119033 +EDGE3 766 815 1.61467 -11.7484 -5.70977 0.00227915 -0.00463423 -0.118802 +EDGE3 767 817 2.36162 -0.00353685 -5.83035 -0.000299935 -0.00267002 0.0028879 +EDGE3 766 817 1.69408 11.7484 -5.9318 0.000647175 -0.000985892 0.124712 +EDGE3 767 816 1.58542 -11.735 -5.68148 0.00705249 -0.00247316 -0.132705 +EDGE3 768 818 2.35609 0.00125962 -5.8409 -0.00293412 -0.000256459 0.00237719 +EDGE3 767 818 1.67878 11.7574 -5.94074 -0.00372422 -0.00789176 0.124747 +EDGE3 768 817 1.59208 -11.7388 -5.70719 -0.000972723 -0.00367923 -0.130308 +EDGE3 769 819 2.3428 0.00528838 -5.81396 0.0099698 0.00592761 0.000996464 +EDGE3 768 819 1.68 11.7645 -5.94348 -0.00662561 0.0011839 0.126268 +EDGE3 769 818 1.58547 -11.7471 -5.71039 -0.00534031 -0.00447617 -0.126057 +EDGE3 770 820 2.35642 -0.015724 -5.8334 0.00885919 -0.012735 -0.00150751 +EDGE3 769 820 1.65933 11.7727 -5.95206 0.00727048 0.0017146 0.12836 +EDGE3 770 819 1.56807 -11.7544 -5.68886 -0.00999196 -0.000599639 -0.12365 +EDGE3 771 821 2.34045 -0.0164303 -5.83977 0.000875369 -0.000805234 0.00310956 +EDGE3 771 820 1.56471 -11.7611 -5.71581 0.00388497 -0.000524425 -0.132602 +EDGE3 770 821 1.65898 11.7688 -5.95753 0.00661046 0.000930338 0.121726 +EDGE3 772 822 2.34529 -0.0031114 -5.81532 -0.0129285 0.00542533 0.00468173 +EDGE3 771 822 1.65778 11.762 -5.92777 0.000284518 0.00562107 0.121511 +EDGE3 772 821 1.55267 -11.7733 -5.7227 -0.00730147 0.00597215 -0.126667 +EDGE3 773 823 2.33611 -0.0174068 -5.84217 -0.00455835 -0.00120224 -0.0116181 +EDGE3 772 823 1.63827 11.774 -5.93868 0.0065783 0.00556819 0.11788 +EDGE3 773 822 1.52841 -11.7637 -5.72346 0.00459595 -0.00685447 -0.122584 +EDGE3 774 824 2.32233 0.00114909 -5.84496 -0.00315661 -0.00584872 0.00251303 +EDGE3 773 824 1.62231 11.7845 -5.95154 -0.000705455 -0.00483397 0.130967 +EDGE3 774 823 1.53855 -11.7713 -5.72862 -0.00326715 0.0014088 -0.11877 +EDGE3 775 825 2.30443 0.00608216 -5.84506 0.00443486 -0.000368812 0.0102086 +EDGE3 774 825 1.62232 11.8014 -5.95453 0.00165345 0.00571035 0.129232 +EDGE3 775 824 1.53151 -11.7709 -5.72372 -0.000159128 0.00170648 -0.124141 +EDGE3 776 826 2.31421 0.00645773 -5.83775 0.000166188 -0.00496248 0.00134926 +EDGE3 775 826 1.61165 11.7989 -5.97367 -0.0136207 0.000411757 0.125325 +EDGE3 776 825 1.51359 -11.8005 -5.71314 -0.00163848 0.00565938 -0.131531 +EDGE3 777 827 2.30154 0.000584579 -5.83959 -0.00289323 0.00221946 -0.00862519 +EDGE3 776 827 1.6201 11.7957 -5.95637 0.00180954 -0.00803954 0.120434 +EDGE3 777 826 1.51781 -11.7793 -5.75011 -0.000488211 0.00100824 -0.125084 +EDGE3 778 828 2.29718 0.0103525 -5.86644 0.00115626 0.00565683 0.00381352 +EDGE3 777 828 1.58972 11.8049 -5.969 -0.00129422 0.00833191 0.121213 +EDGE3 778 827 1.52038 -11.7845 -5.72544 0.00097092 0.00264396 -0.121752 +EDGE3 779 829 2.29019 -0.00813538 -5.85039 -0.0107214 -0.00483326 -0.00259556 +EDGE3 778 829 1.5853 11.8098 -5.97965 -0.00658705 -0.00642227 0.12378 +EDGE3 779 828 1.50032 -11.8248 -5.73226 -0.00241595 0.0058126 -0.12724 +EDGE3 779 830 1.57913 11.8529 -5.98043 -0.00753491 0.000572819 0.129971 +EDGE3 780 830 2.28012 0.0119239 -5.84863 -0.00452717 -0.000116882 0.00252775 +EDGE3 780 829 1.49996 -11.8243 -5.73722 0.000398777 0.00190652 -0.126359 +EDGE3 781 831 2.27622 -0.00466227 -5.86175 -0.00974654 0.00201948 -0.00640202 +EDGE3 780 831 1.57853 11.8286 -5.96491 -0.0034699 0.00533165 0.125629 +EDGE3 781 830 1.47864 -11.808 -5.72904 0.00706209 0.00675502 -0.124853 +EDGE3 782 832 2.27822 -0.0118531 -5.85955 -0.0103146 0.00027783 -0.0139776 +EDGE3 781 832 1.55894 11.8119 -5.97689 -0.0015111 -0.0023653 0.115973 +EDGE3 782 831 1.48201 -11.8276 -5.72841 -0.00341147 0.00855101 -0.132046 +EDGE3 783 833 2.25905 0.00459392 -5.86525 -0.00635833 0.00193513 0.00948059 +EDGE3 782 833 1.5652 11.8459 -5.9756 -0.00402785 -0.00259595 0.126121 +EDGE3 783 832 1.46858 -11.8351 -5.74806 0.00306129 -0.00605431 -0.132478 +EDGE3 784 834 2.2525 0.00670814 -5.87458 -1.3725e-05 -0.000500015 -0.00455497 +EDGE3 783 834 1.55862 11.8284 -5.97433 -0.00293594 -0.00460503 0.117999 +EDGE3 784 833 1.46485 -11.8627 -5.73479 -0.00056449 0.00604493 -0.130379 +EDGE3 785 835 2.22867 0.0104561 -5.87824 -0.00438847 -0.00161596 0.000382377 +EDGE3 784 835 1.54125 11.8495 -5.98116 0.0028911 -0.000866683 0.128766 +EDGE3 785 834 1.44776 -11.8591 -5.75772 -0.00293175 0.00733414 -0.118731 +EDGE3 786 836 2.20225 -0.0166318 -5.87197 -0.00288248 -0.00372957 0.00235901 +EDGE3 785 836 1.52265 11.859 -5.98208 0.0022426 -0.00102325 0.130689 +EDGE3 786 835 1.44394 -11.8264 -5.74712 0.00711199 -0.0139865 -0.123999 +EDGE3 787 837 2.23627 0.000318812 -5.88383 -0.00158641 -0.00708874 0.00537359 +EDGE3 786 837 1.51416 11.8741 -5.99676 0.0025882 0.00113388 0.128977 +EDGE3 787 836 1.44243 -11.8343 -5.76797 -0.00313238 0.00603102 -0.132128 +EDGE3 788 838 2.20994 -0.00772375 -5.87653 -0.00562642 -0.00389846 -0.00315921 +EDGE3 788 837 1.43915 -11.8627 -5.76639 0.00467388 -0.00535555 -0.133307 +EDGE3 787 838 1.5206 11.85 -6.0023 0.00268599 0.000327385 0.124747 +EDGE3 789 839 2.20668 0.0269647 -5.86293 -0.00455173 0.0011404 -0.00562433 +EDGE3 788 839 1.50534 11.8688 -5.98779 0.00886853 0.00455737 0.124759 +EDGE3 789 838 1.41361 -11.8568 -5.76536 0.00056457 -0.0109216 -0.122226 +EDGE3 790 840 2.20846 0.0263834 -5.89106 -0.00301806 -0.00117535 0.0024286 +EDGE3 789 840 1.5024 11.8716 -6.00305 0.00151108 0.00338537 0.136517 +EDGE3 790 839 1.41067 -11.8801 -5.7667 -3.20962e-06 -0.00602139 -0.11901 +EDGE3 791 841 2.20242 -0.015531 -5.87671 4.21545e-05 -0.00448403 -0.00478215 +EDGE3 790 841 1.49929 11.8726 -5.9947 0.00655279 0.00151526 0.133473 +EDGE3 791 840 1.40448 -11.8805 -5.75656 0.00118258 0.00146309 -0.122024 +EDGE3 792 842 2.18844 -0.0073256 -5.89235 0.00491152 0.00134138 0.000344377 +EDGE3 791 842 1.49454 11.872 -6.0204 -0.00867807 -0.000525844 0.13073 +EDGE3 792 841 1.40798 -11.8802 -5.76872 0.00241327 0.00337141 -0.123819 +EDGE3 793 843 2.19917 -0.00172866 -5.87151 0.00651196 0.00693405 -0.00932789 +EDGE3 792 843 1.47361 11.8856 -6.00021 0.00891963 -0.0017126 0.126203 +EDGE3 793 842 1.39117 -11.8724 -5.78787 -0.00659695 -0.00316663 -0.124642 +EDGE3 794 844 2.17287 0.00469166 -5.89256 -0.00806472 0.000162006 -0.00233831 +EDGE3 793 844 1.47193 11.8888 -6.01435 0.00531479 0.00153998 0.129016 +EDGE3 794 843 1.38228 -11.8924 -5.76654 0.000636554 0.00027774 -0.128424 +EDGE3 795 845 2.14913 0.0140983 -5.90015 0.000483149 -0.00574998 0.00123381 +EDGE3 794 845 1.46553 11.8997 -6.00652 0.00374126 0.000824085 0.127738 +EDGE3 795 844 1.38026 -11.8971 -5.76149 0.00684816 -0.00125273 -0.124882 +EDGE3 796 846 2.16039 -0.0119012 -5.89813 0.00248492 0.00107182 -0.00773043 +EDGE3 795 846 1.44026 11.8981 -6.02666 0.00610419 0.00165284 0.119723 +EDGE3 796 845 1.38256 -11.8971 -5.76901 0.00638999 -0.00479558 -0.121643 +EDGE3 797 847 2.15936 0.0101284 -5.88508 0.00516548 -0.00486083 -0.00177277 +EDGE3 796 847 1.42453 11.9201 -6.01446 -0.00149711 0.00176946 0.127138 +EDGE3 797 846 1.3539 -11.889 -5.77288 0.000471518 -0.00236871 -0.131544 +EDGE3 798 848 2.13683 0.0120661 -5.90911 -0.00309 0.00175106 0.00698358 +EDGE3 797 848 1.43051 11.9158 -6.01548 0.00230236 -0.0049842 0.126844 +EDGE3 798 847 1.33728 -11.916 -5.77396 -0.0030096 0.00324108 -0.127116 +EDGE3 799 849 2.14226 -0.00345139 -5.92105 -0.00298886 0.00425502 0.00713835 +EDGE3 798 849 1.41803 11.9208 -6.0239 0.0035133 -0.00182312 0.13646 +EDGE3 799 848 1.35052 -11.9291 -5.78795 0.00213228 -0.0021464 -0.127067 +EDGE3 800 850 2.12183 0.00835586 -5.90667 0.00203609 0.000633491 -0.00034584 +EDGE3 799 850 1.41943 11.9307 -6.02957 0.00739703 -0.0065112 0.124379 +EDGE3 800 849 1.35091 -11.9332 -5.78827 0.00226706 -0.00129218 -0.132554 +EDGE3 801 851 2.11771 0.00183574 -5.92255 -0.00310879 0.00373037 0.000911997 +EDGE3 800 851 1.41028 11.9312 -6.02498 -0.00256509 0.0017658 0.122763 +EDGE3 801 850 1.3312 -11.9281 -5.78416 0.000849618 0.00269227 -0.135984 +EDGE3 802 852 2.11466 0.00090054 -5.91369 -0.00816507 -0.000486031 0.00764242 +EDGE3 801 852 1.42525 11.9392 -6.03149 -0.0124395 -0.00506436 0.132093 +EDGE3 802 851 1.31879 -11.9297 -5.79954 0.00295144 0.00532936 -0.123534 +EDGE3 803 853 2.11082 0.0184593 -5.91063 -0.00326166 0.00137206 -0.00279012 +EDGE3 802 853 1.39312 11.9517 -6.03645 -0.00656968 -0.000576831 0.124818 +EDGE3 803 852 1.31083 -11.9452 -5.80912 -0.000805925 0.00450235 -0.13459 +EDGE3 804 854 2.1 -0.00369457 -5.92381 -0.00281142 0.000289088 -0.00326611 +EDGE3 803 854 1.38103 11.9353 -6.0273 0.00261358 -0.00870923 0.110411 +EDGE3 804 853 1.30271 -11.9566 -5.80023 0.000513715 -0.00476877 -0.121892 +EDGE3 805 855 2.07198 0.0223091 -5.9212 0.00489448 -0.00206859 0.000881145 +EDGE3 804 855 1.39704 11.9513 -6.04575 -0.00153853 -0.00044917 0.119971 +EDGE3 805 854 1.31011 -11.924 -5.79439 0.00980786 -0.0023212 -0.121993 +EDGE3 806 856 2.09121 -0.0114145 -5.92155 -0.00446858 -0.00138703 -0.004147 +EDGE3 805 856 1.38923 11.9561 -6.04233 0.00451395 0.00117857 0.11787 +EDGE3 806 855 1.31303 -11.9325 -5.81215 0.00868416 0.00423995 -0.122288 +EDGE3 807 857 2.08352 0.0179574 -5.93465 0.000787709 -0.00372004 -0.00592673 +EDGE3 806 857 1.36521 11.9756 -6.03244 -0.00196637 0.00275095 0.120353 +EDGE3 807 856 1.30193 -11.9248 -5.80813 0.00719633 -0.0033603 -0.120421 +EDGE3 808 858 2.06451 -0.0010456 -5.95028 -0.0013471 0.000597734 0.00959404 +EDGE3 807 858 1.35194 11.9572 -6.03827 0.00398403 0.00286554 0.12354 +EDGE3 808 857 1.27168 -11.9569 -5.81141 0.00757422 0.000868616 -0.125726 +EDGE3 809 859 2.03881 0.00478169 -5.9432 -0.00445308 0.00396269 0.00189575 +EDGE3 808 859 1.34127 11.9617 -6.03625 0.00333183 -0.00182063 0.130661 +EDGE3 809 858 1.26963 -11.9563 -5.81285 0.00561401 -0.00654724 -0.123102 +EDGE3 810 860 2.05279 -0.0360266 -5.94892 0.00692252 -0.00730895 -0.00200445 +EDGE3 809 860 1.36653 11.9721 -6.07186 0.00159884 -0.00505428 0.126014 +EDGE3 810 859 1.26909 -11.9822 -5.81107 -0.0113513 0.00691894 -0.127442 +EDGE3 811 861 2.04279 -0.00875178 -5.93205 0.00131231 0.00566204 0.00116875 +EDGE3 810 861 1.33482 11.9823 -6.0613 -0.010452 0.012496 0.112736 +EDGE3 811 860 1.26341 -11.9628 -5.83049 -0.00053054 -0.00323956 -0.124311 +EDGE3 812 862 2.03901 0.00205241 -5.94527 0.0129708 -0.00432974 -0.0049913 +EDGE3 811 862 1.32805 11.9735 -6.05676 -0.00204589 -0.0068969 0.128208 +EDGE3 812 861 1.23236 -11.9828 -5.83235 0.00582818 0.00391764 -0.131285 +EDGE3 812 863 1.31751 11.9647 -6.06081 -0.00150118 0.00202978 0.122796 +EDGE3 813 863 2.01825 -0.0123959 -5.93405 0.00274168 -0.00759239 -0.00330288 +EDGE3 813 862 1.22483 -11.9621 -5.81909 0.00565927 0.00722911 -0.125605 +EDGE3 813 864 1.30125 11.9957 -6.06483 -0.00468812 -0.00440993 0.12787 +EDGE3 814 864 2.01733 0.0175112 -5.9454 0.000379654 -0.00347433 0.00632795 +EDGE3 815 865 2.00621 0.00824656 -5.94439 -0.000416067 -0.00131415 0.00610232 +EDGE3 814 863 1.22946 -11.9797 -5.8318 0.0121469 0.00218449 -0.135827 +EDGE3 814 865 1.30495 12.0033 -6.05073 -0.00494651 -0.000425304 0.122771 +EDGE3 815 864 1.21952 -11.978 -5.82741 -0.00190253 -0.00145659 -0.127208 +EDGE3 816 866 1.99517 -0.00952941 -5.96915 0.000505084 0.00355317 -0.000180049 +EDGE3 815 866 1.28615 12.0055 -6.0727 -0.00486554 -0.00292437 0.129121 +EDGE3 816 865 1.23102 -11.9836 -5.8455 0.00140198 -0.00398878 -0.119996 +EDGE3 816 867 1.30001 12.0156 -6.07725 0.00663726 -0.0125419 0.124771 +EDGE3 817 867 2.00314 -0.0195482 -5.95368 0.00466738 -0.00297114 -0.00223317 +EDGE3 818 868 1.9967 0.00828371 -5.94664 0.00293717 0.00110017 0.000618502 +EDGE3 817 866 1.20405 -12.0015 -5.84681 -0.00342883 -0.00394411 -0.130552 +EDGE3 818 867 1.19803 -11.9969 -5.82647 0.0070656 -0.00843305 -0.128768 +EDGE3 817 868 1.2806 11.9952 -6.07368 -0.00534044 -0.000147634 0.127624 +EDGE3 818 869 1.26123 12.0202 -6.08151 -0.00402094 0.00481498 0.132381 +EDGE3 819 869 1.96988 -0.00204691 -5.94443 0.00362112 0.00578664 -0.0019223 +EDGE3 820 870 1.96576 -0.00742169 -5.96893 -0.00435902 -0.00534314 0.00168526 +EDGE3 819 868 1.18034 -11.9947 -5.83194 -0.00324608 -0.00584593 -0.123678 +EDGE3 819 870 1.24913 12.0179 -6.07748 -0.00588493 -0.00348182 0.13098 +EDGE3 820 869 1.18857 -12.0162 -5.83638 -0.00189752 4.03866e-05 -0.122603 +EDGE3 821 871 1.98569 0.000595772 -5.95102 -0.000451126 0.000456551 -5.67083e-05 +EDGE3 820 871 1.25142 12.0216 -6.08728 -0.00109074 0.00502821 0.127873 +EDGE3 821 870 1.17613 -12.0083 -5.84926 0.00055611 -0.000877783 -0.130604 +EDGE3 821 872 1.25174 12.0388 -6.0813 -0.0124639 -0.000261302 0.1262 +EDGE3 822 872 1.96864 0.0058054 -5.97447 0.00646916 0.0120133 -0.00338049 +EDGE3 822 871 1.17205 -12.0007 -5.85346 -0.00252318 0.0116096 -0.120951 +EDGE3 823 873 1.94475 -0.00086957 -5.95224 -0.000632581 0.00726937 0.00773686 +EDGE3 822 873 1.23163 12.0229 -6.08206 0.0059614 0.00249595 0.122742 +EDGE3 823 872 1.14471 -12.0175 -5.86091 0.00409297 -0.00305164 -0.126103 +EDGE3 824 874 1.94045 -0.00471709 -5.94966 -0.00897789 -0.00288969 -0.0031815 +EDGE3 823 874 1.24903 12.0351 -6.09854 -0.000299568 -0.00956158 0.130713 +EDGE3 825 875 1.95462 0.00261263 -5.97892 0.00483919 0.0103772 0.00371967 +EDGE3 824 873 1.14305 -12.0353 -5.84427 -0.00458908 -0.00573016 -0.121229 +EDGE3 825 874 1.15079 -12.046 -5.85357 -0.000188872 0.0050351 -0.126219 +EDGE3 824 875 1.21542 12.0342 -6.09054 -0.00419864 -0.00232028 0.129019 +EDGE3 826 876 1.92898 -0.00485005 -5.98265 0.00706413 -0.00673247 0.000315243 +EDGE3 825 876 1.19932 12.0212 -6.10688 -0.000634171 0.00601971 0.120119 +EDGE3 826 875 1.13747 -12.0342 -5.85053 -0.00474757 0.00836684 -0.123599 +EDGE3 826 877 1.20725 12.059 -6.0968 0.00617517 -0.00614817 0.129675 +EDGE3 827 877 1.92491 0.00333346 -5.96861 0.00547675 0.000568531 0.000165878 +EDGE3 827 876 1.13982 -12.0331 -5.86936 -0.00229788 0.00243665 -0.124378 +EDGE3 828 878 1.90855 0.00456295 -5.97841 0.000674254 -0.00527596 0.000600599 +EDGE3 827 878 1.20983 12.059 -6.11937 0.0119959 0.00376439 0.125582 +EDGE3 828 877 1.12751 -12.039 -5.85306 0.00813642 -0.00814409 -0.127482 +EDGE3 829 879 1.91022 -0.0034828 -5.98332 0.0052853 0.00304796 -0.00624285 +EDGE3 829 878 1.1125 -12.0619 -5.85758 0.0047023 -0.0041127 -0.124813 +EDGE3 828 879 1.18423 12.044 -6.0827 0.000654356 0.00214317 0.1338 +EDGE3 829 880 1.18007 12.0524 -6.09856 0.00511994 -0.00529767 0.131159 +EDGE3 830 880 1.91754 -0.0130844 -5.99138 -0.00414606 0.000184111 0.00519203 +EDGE3 831 881 1.89052 0.00620731 -5.99503 -0.00782829 -0.000867404 -0.000525781 +EDGE3 830 879 1.12112 -12.0412 -5.88083 -0.00502852 -0.00549515 -0.126966 +EDGE3 830 881 1.17349 12.0592 -6.12603 -0.000897118 0.00619145 0.125878 +EDGE3 831 880 1.09745 -12.0624 -5.87337 -0.0110797 -0.00455032 -0.133957 +EDGE3 832 882 1.88034 -0.018567 -5.99428 -0.000274963 0.000299098 -0.00279299 +EDGE3 831 882 1.1784 12.0715 -6.11607 -0.00778558 0.000734624 0.137145 +EDGE3 832 881 1.1001 -12.0675 -5.8887 -1.30697e-05 0.00597958 -0.128258 +EDGE3 832 883 1.15917 12.0459 -6.10891 0.00847446 -0.000653668 0.131233 +EDGE3 833 883 1.89705 0.0049625 -5.98265 0.00176224 -0.00265363 0.00100641 +EDGE3 834 884 1.88257 -0.00786731 -6.00022 -0.00930213 0.00369157 0.0047952 +EDGE3 833 882 1.07875 -12.0525 -5.8692 0.00770437 -0.00393323 -0.128796 +EDGE3 834 883 1.07537 -12.0728 -5.88813 -0.00436731 0.00204486 -0.131782 +EDGE3 833 884 1.17887 12.0597 -6.10366 -0.00489365 0.0132128 0.118988 +EDGE3 834 885 1.15357 12.0776 -6.12194 0.00825521 0.00345653 0.121427 +EDGE3 835 885 1.87629 0.0093865 -6.01616 0.00763092 0.00534127 0.00246453 +EDGE3 836 886 1.85448 0.0177185 -6.01067 0.00726836 0.00323789 -0.00497609 +EDGE3 835 884 1.06264 -12.0732 -5.86573 -0.00369827 -0.00254005 -0.117925 +EDGE3 836 885 1.05656 -12.0879 -5.87386 0.00503274 0.000303769 -0.122103 +EDGE3 835 886 1.13211 12.0816 -6.11614 -0.000559163 0.00072707 0.129207 +EDGE3 836 887 1.12955 12.0806 -6.13527 0.00527254 0.00114159 0.127345 +EDGE3 837 887 1.86391 -0.0189603 -5.99865 0.00223615 -0.00399944 -0.0076471 +EDGE3 838 888 1.84743 0.00436205 -6.01063 -0.000926747 0.00774537 -0.00418757 +EDGE3 837 886 1.04196 -12.1109 -5.87953 0.000367893 0.00806824 -0.125757 +EDGE3 837 888 1.12836 12.0937 -6.13301 0.00258518 -0.00081878 0.117884 +EDGE3 838 887 1.06071 -12.0838 -5.87317 0.00309489 0.00303682 -0.125075 +EDGE3 838 889 1.11742 12.1086 -6.14732 0.0104823 0.00688199 0.129708 +EDGE3 839 889 1.85233 0.013385 -5.98314 0.00461622 -0.00870684 0.00269726 +EDGE3 839 888 1.04296 -12.0918 -5.88239 0.00280295 -0.00557242 -0.13233 +EDGE3 840 890 1.82701 -0.00119477 -6.0139 0.00407334 0.00311346 -0.0011379 +EDGE3 840 889 1.02703 -12.0967 -5.86052 -0.00412497 0.00247381 -0.120496 +EDGE3 839 890 1.12033 12.1055 -6.13767 0.00192801 0.00308989 0.126685 +EDGE3 841 891 1.82079 0.00863532 -6.01247 -0.000306694 -0.00188889 0.00218368 +EDGE3 840 891 1.10712 12.0958 -6.13449 0.00280643 -0.000619347 0.129744 +EDGE3 841 890 1.02577 -12.1112 -5.88499 -0.00068308 -0.00222606 -0.127475 +EDGE3 841 892 1.10666 12.1189 -6.13215 0.00331988 0.000472936 0.125466 +EDGE3 842 892 1.81943 0.00523215 -6.00412 -0.000829264 0.002805 0.00665456 +EDGE3 843 893 1.80855 0.00351855 -6.02545 -0.00138023 0.00699898 0.00071884 +EDGE3 842 891 1.03033 -12.1197 -5.89151 0.00529102 0.00594643 -0.124302 +EDGE3 843 892 1.00706 -12.105 -5.89848 -0.00739648 -0.00287963 -0.124247 +EDGE3 842 893 1.08225 12.1028 -6.14152 0.00850283 -0.00113 0.124778 +EDGE3 843 894 1.08295 12.1147 -6.15282 0.00365233 0.00914247 0.12391 +EDGE3 844 894 1.78995 0.00688332 -6.01553 0.00518344 -0.00373122 0.000391933 +EDGE3 844 893 0.985032 -12.1246 -5.89632 -0.000744154 0.00184531 -0.129614 +EDGE3 845 895 1.78687 -0.0120422 -6.0248 0.00520436 0.00501177 0.000781545 +EDGE3 845 894 1.00333 -12.1346 -5.90772 -0.00495757 -0.00200142 -0.118333 +EDGE3 844 895 1.0725 12.1075 -6.13354 -0.00285752 -0.00662632 0.126513 +EDGE3 845 896 1.06546 12.1098 -6.13842 0.0045627 0.00649236 0.125209 +EDGE3 846 896 1.7727 -0.00112547 -6.0173 -0.000300849 0.00471429 0.0107027 +EDGE3 846 895 0.999341 -12.1093 -5.87985 -0.00203697 -0.00482931 -0.124826 +EDGE3 847 897 1.78398 -0.00962529 -6.0137 -0.000549791 0.00415667 -0.00501239 +EDGE3 846 897 1.0539 12.1456 -6.13956 -0.00500197 -0.00258688 0.124993 +EDGE3 848 898 1.76866 0.00494662 -6.02821 0.00468551 -0.00380313 -0.000102201 +EDGE3 847 896 0.969113 -12.1089 -5.93698 0.00530942 0.00112415 -0.13791 +EDGE3 847 898 1.05317 12.1346 -6.15158 0.00209412 0.00690479 0.126024 +EDGE3 848 897 0.967358 -12.1404 -5.89336 0.00551052 -0.00353007 -0.125277 +EDGE3 848 899 1.02211 12.1345 -6.15058 0.00200652 0.00657007 0.121114 +EDGE3 849 899 1.74233 -0.00443813 -6.00945 -0.00127707 0.0105347 -0.00405627 +EDGE3 850 900 1.75994 -0.0110252 -6.0417 0.000177874 0.0068535 -0.00228921 +EDGE3 849 898 0.957754 -12.1386 -5.90976 -0.00589716 0.000945099 -0.133445 +EDGE3 850 899 0.963021 -12.1377 -5.91003 -0.00611099 0.00562652 -0.127994 +EDGE3 849 900 1.00599 12.1247 -6.14967 0.00502904 -0.000145953 0.129866 +EDGE3 851 901 1.75193 -0.0136552 -6.02672 -0.00968263 0.0021221 -0.0113579 +EDGE3 850 901 1.02124 12.1395 -6.14486 -0.00490352 -0.00384582 0.130802 +EDGE3 851 900 0.951048 -12.1305 -5.92725 -0.00290695 0.00630252 -0.131805 +EDGE3 852 902 1.73727 -0.00200656 -6.04841 0.00347953 -0.000244478 -0.00137436 +EDGE3 851 902 1.03155 12.1434 -6.13294 0.00283438 -0.00239452 0.122608 +EDGE3 852 901 0.948104 -12.1445 -5.90517 0.0021509 -0.000524806 -0.127449 +EDGE3 853 903 1.72089 -0.00447584 -6.03902 -0.00768025 0.00199358 -0.00353719 +EDGE3 852 903 1.01602 12.1314 -6.15592 -0.00364084 0.00146694 0.123206 +EDGE3 853 902 0.921932 -12.1448 -5.91816 0.0036389 -0.0038507 -0.117518 +EDGE3 854 904 1.72371 -0.0177653 -6.04172 0.00333064 -0.00514626 0.0101329 +EDGE3 853 904 1.00546 12.1493 -6.17103 0.00114648 0.00341822 0.129316 +EDGE3 854 903 0.935676 -12.1376 -5.90471 0.00321629 -0.00433544 -0.121459 +EDGE3 855 905 1.71626 0.00651119 -6.05882 0.00656925 -0.000570821 0.00546282 +EDGE3 854 905 0.987057 12.1605 -6.19165 0.00925539 -0.00484159 0.125551 +EDGE3 855 904 0.90712 -12.1479 -5.90574 0.00160784 -0.00346108 -0.127273 +EDGE3 856 906 1.73036 0.0108288 -6.05166 0.00502372 -0.0082705 -0.0116607 +EDGE3 855 906 0.988125 12.158 -6.16958 0.00478877 -0.00335011 0.129412 +EDGE3 856 905 0.893349 -12.1531 -5.93359 0.0103584 -0.00350634 -0.126353 +EDGE3 857 907 1.70832 0.00847832 -6.05125 -0.0017711 -0.00548456 0.00028176 +EDGE3 856 907 0.987051 12.1729 -6.18985 0.000870794 0.00425425 0.126962 +EDGE3 857 906 0.896643 -12.1714 -5.9409 -0.00096852 0.00264136 -0.133063 +EDGE3 858 908 1.70222 -0.00403641 -6.03752 -0.00355917 0.00093064 0.00694135 +EDGE3 857 908 0.961097 12.1732 -6.18767 0.00145094 0.00818253 0.128464 +EDGE3 858 907 0.90734 -12.1826 -5.93642 0.0115288 -0.00278476 -0.127775 +EDGE3 859 909 1.69986 0.0133803 -6.05764 0.00699989 0.00833856 -0.000837243 +EDGE3 858 909 0.952814 12.1773 -6.18313 0.00616611 0.00298787 0.128652 +EDGE3 859 908 0.894945 -12.1824 -5.91862 0.00387565 -0.00205963 -0.129095 +EDGE3 860 910 1.68044 -0.00254566 -6.05477 -0.00331513 0.00528609 0.00829555 +EDGE3 859 910 0.936177 12.1944 -6.16529 0.00392529 -0.00101161 0.118349 +EDGE3 860 909 0.894087 -12.1521 -5.94064 0.00102497 0.00436984 -0.119418 +EDGE3 861 911 1.67161 0.00743957 -6.04603 -0.00213043 0.00430212 0.0007115 +EDGE3 860 911 0.946767 12.1728 -6.17717 -0.00412537 0.00663372 0.133674 +EDGE3 861 910 0.861401 -12.1614 -5.93884 0.00250769 -0.00350423 -0.131213 +EDGE3 862 912 1.66932 -0.0110147 -6.06506 0.00995457 0.00368497 -0.00731657 +EDGE3 861 912 0.93691 12.1949 -6.18219 -0.00145821 0.00724876 0.120568 +EDGE3 862 911 0.851515 -12.1866 -5.9339 -0.00164256 0.00405475 -0.128201 +EDGE3 863 913 1.63624 0.000861727 -6.0542 -0.000455248 0.000629157 -0.0126124 +EDGE3 862 913 0.928728 12.1815 -6.17682 0.0085481 -9.85677e-05 0.124301 +EDGE3 863 912 0.873728 -12.1864 -5.937 -0.00182943 0.00882066 -0.130999 +EDGE3 864 914 1.64629 0.000176364 -6.0733 -0.00941336 -0.011222 0.00107066 +EDGE3 863 914 0.921106 12.2043 -6.18302 -0.00026931 -0.000630394 0.126036 +EDGE3 864 913 0.841436 -12.197 -5.93628 0.00837586 -0.00219594 -0.129531 +EDGE3 865 915 1.63942 0.00149199 -6.06084 -0.000498063 -0.00585475 -0.00130138 +EDGE3 864 915 0.912925 12.2036 -6.19159 -0.00301541 -0.00214707 0.123589 +EDGE3 865 914 0.837615 -12.204 -5.9429 0.000741937 0.00373998 -0.120397 +EDGE3 866 916 1.62956 -0.0054475 -6.06615 0.00156917 0.00212585 0.00784586 +EDGE3 865 916 0.881087 12.2207 -6.1928 0.00155757 -0.0028791 0.124223 +EDGE3 866 915 0.828413 -12.2158 -5.93621 -0.00205591 -0.00664818 -0.123616 +EDGE3 867 917 1.63005 -0.0129665 -6.06856 -0.00152699 0.00622885 0.00600017 +EDGE3 866 917 0.875732 12.2051 -6.19175 0.00375506 -0.0022796 0.120874 +EDGE3 867 916 0.827703 -12.2061 -5.95116 0.00120195 -0.00155964 -0.122963 +EDGE3 868 918 1.60684 -0.00078039 -6.07056 0.00793164 -0.0111246 -0.00470944 +EDGE3 867 918 0.868928 12.2086 -6.18927 0.00917531 0.00317103 0.130605 +EDGE3 868 917 0.813612 -12.2091 -5.96986 0.000674705 -0.00110597 -0.122131 +EDGE3 869 919 1.58308 0.0185352 -6.06952 -0.00567149 0.00128495 -0.0044895 +EDGE3 868 919 0.886536 12.1993 -6.20133 -0.00235097 -0.00229109 0.126136 +EDGE3 869 918 0.828037 -12.2034 -5.95527 -0.00411932 0.000688125 -0.127839 +EDGE3 870 920 1.59281 0.0133142 -6.07326 -0.00977118 -0.00298965 0.00314698 +EDGE3 869 920 0.871665 12.2238 -6.19068 0.00492663 -0.00716624 0.131081 +EDGE3 870 919 0.809862 -12.2142 -5.96098 0.00278095 0.00453759 -0.121608 +EDGE3 871 921 1.58727 0.0191441 -6.06746 -0.00396078 0.00337828 -0.00346538 +EDGE3 870 921 0.855889 12.2296 -6.20137 0.00202137 0.00372579 0.120692 +EDGE3 871 920 0.799123 -12.2143 -5.95002 -0.00536295 0.00672357 -0.129208 +EDGE3 872 922 1.60099 -0.0126592 -6.07414 -0.000342814 -0.00457794 0.00504796 +EDGE3 871 922 0.85305 12.2021 -6.19878 0.00571845 -0.00315179 0.11948 +EDGE3 872 921 0.794637 -12.2306 -5.9538 -0.00556701 0.00948214 -0.130115 +EDGE3 873 923 1.57293 -0.00456019 -6.09199 0.00851155 0.0049535 0.0114109 +EDGE3 872 923 0.849978 12.2158 -6.18073 0.00295018 0.00437693 0.126106 +EDGE3 873 922 0.75217 -12.216 -5.96262 0.00120852 -0.00246669 -0.128349 +EDGE3 874 924 1.56831 -0.00338196 -6.06418 -0.00736727 -0.00961187 -0.00631643 +EDGE3 873 924 0.837831 12.2281 -6.18556 -0.00477589 0.00215686 0.126829 +EDGE3 874 923 0.770795 -12.2328 -5.96428 -0.00489889 -0.00705048 -0.115828 +EDGE3 875 925 1.57146 0.0155599 -6.08796 0.00267395 -0.00216922 0.0097358 +EDGE3 874 925 0.834774 12.2434 -6.2105 -0.00131976 0.00686627 0.135601 +EDGE3 875 924 0.762562 -12.2267 -5.95707 0.00701006 -0.00714314 -0.127384 +EDGE3 876 926 1.54517 0.0264433 -6.09614 0.00476846 -0.00207043 -0.00196642 +EDGE3 875 926 0.802388 12.2413 -6.19781 0.00826718 0.00519418 0.121495 +EDGE3 876 925 0.765895 -12.236 -5.96017 -0.00770301 -0.00970274 -0.121337 +EDGE3 877 927 1.54941 -0.0101766 -6.09442 -0.000880471 0.00228689 -0.00484935 +EDGE3 876 927 0.78783 12.2345 -6.2067 -0.0113938 0.00327799 0.125381 +EDGE3 877 926 0.728308 -12.2376 -5.9504 -0.00275042 -0.00272258 -0.124298 +EDGE3 878 928 1.53842 0.00511774 -6.08875 0.00420479 9.21229e-05 0.0102586 +EDGE3 877 928 0.805904 12.2389 -6.22681 0.00411265 0.000692376 0.121956 +EDGE3 878 927 0.730931 -12.2332 -5.95711 0.00401833 0.00442824 -0.127114 +EDGE3 879 929 1.54388 0.00564821 -6.07967 -0.00466938 -0.00629668 0.0071779 +EDGE3 878 929 0.806145 12.2479 -6.22518 0.00630658 -0.00331757 0.124001 +EDGE3 879 928 0.734654 -12.2359 -5.96993 0.0024339 -0.0064463 -0.124547 +EDGE3 880 930 1.52092 -0.0200736 -6.07815 0.00223972 -0.00481296 -0.0037577 +EDGE3 879 930 0.793747 12.2556 -6.23158 -0.0143903 0.00424964 0.121178 +EDGE3 880 929 0.736986 -12.2593 -5.96658 0.00222248 -0.00149305 -0.128842 +EDGE3 881 931 1.52796 -0.0162652 -6.10854 -0.0029415 -0.00325457 0.0177393 +EDGE3 880 931 0.796325 12.238 -6.22134 0.00772182 -0.00155858 0.128357 +EDGE3 881 930 0.730585 -12.2594 -5.98845 -0.00622949 -0.00468509 -0.117277 +EDGE3 882 932 1.51505 0.0188581 -6.11323 0.00171375 0.00334658 -0.00954714 +EDGE3 881 932 0.764653 12.2508 -6.21282 -0.00785029 0.00953886 0.1178 +EDGE3 882 931 0.691332 -12.2274 -5.99057 -0.00124746 0.00108924 -0.127497 +EDGE3 883 933 1.49359 0.0191942 -6.11118 0.00444573 0.00710988 0.00570388 +EDGE3 882 933 0.750185 12.2543 -6.21952 -0.00365167 0.00978427 0.11995 +EDGE3 883 932 0.689432 -12.2537 -5.94878 0.00322838 -0.00191524 -0.118898 +EDGE3 884 934 1.48516 0.0278332 -6.10104 -0.006499 0.00178763 0.000342488 +EDGE3 883 934 0.749413 12.265 -6.2198 0.00123555 -0.00221853 0.126192 +EDGE3 884 933 0.68917 -12.2662 -5.98565 -0.00149517 -0.00566414 -0.127329 +EDGE3 885 935 1.46994 0.00102549 -6.10823 -0.00154801 0.0019736 -0.00394332 +EDGE3 884 935 0.76727 12.2525 -6.21259 -0.00199341 -0.0031217 0.122212 +EDGE3 885 934 0.679759 -12.2553 -5.98225 -0.00335947 0.00281087 -0.118889 +EDGE3 886 936 1.48404 0.00578128 -6.09789 -0.00224585 -0.00981119 0.00233621 +EDGE3 885 936 0.753603 12.2389 -6.2224 0.00628623 0.00660957 0.133052 +EDGE3 886 935 0.674955 -12.2544 -5.997 -0.00204275 0.000749662 -0.128678 +EDGE3 887 937 1.47697 0.00273799 -6.09659 -0.00587024 -0.00413905 0.00425405 +EDGE3 886 937 0.721961 12.2736 -6.22921 -0.00680653 -0.00687626 0.126839 +EDGE3 887 936 0.684002 -12.2603 -5.97549 0.00431096 0.00133943 -0.127448 +EDGE3 888 938 1.47392 0.0147619 -6.09011 0.00465732 -0.0016465 -0.00917904 +EDGE3 887 938 0.717436 12.2814 -6.24298 0.00502734 0.00485527 0.125542 +EDGE3 888 937 0.655543 -12.2714 -5.98309 -0.000586057 -0.00625423 -0.124608 +EDGE3 889 939 1.44882 -0.00275644 -6.11854 -0.00508675 -0.000227348 -0.00427255 +EDGE3 888 939 0.7247 12.2885 -6.24637 0.00754575 0.00889299 0.115665 +EDGE3 889 938 0.650713 -12.2627 -5.99132 0.00490747 -0.0040527 -0.121805 +EDGE3 890 940 1.42707 -0.00399678 -6.10228 -0.00344419 0.000887015 0.00202043 +EDGE3 889 940 0.727586 12.2629 -6.23353 9.95735e-05 -0.0028624 0.12088 +EDGE3 890 939 0.657739 -12.2772 -5.98493 0.00400031 -0.00461732 -0.115389 +EDGE3 891 941 1.42865 -0.00266502 -6.12498 -0.00672694 -0.00680511 0.000299843 +EDGE3 890 941 0.710973 12.2793 -6.24239 0.00897506 -0.00219723 0.126502 +EDGE3 891 940 0.629808 -12.2762 -6.00218 0.000216954 0.00451187 -0.130954 +EDGE3 892 942 1.42348 0.00908154 -6.1202 0.0034079 -0.000573099 -0.000884965 +EDGE3 891 942 0.690669 12.2905 -6.23199 0.000951298 0.0156951 0.133277 +EDGE3 892 941 0.628498 -12.286 -5.98537 -0.00286556 -0.00623093 -0.133582 +EDGE3 893 943 1.43374 -0.0147197 -6.12995 -0.00397117 0.00132482 0.00760863 +EDGE3 892 943 0.69171 12.2884 -6.24057 0.00974778 0.000734885 0.1236 +EDGE3 893 942 0.629189 -12.3093 -6.00316 0.000404133 -0.00128007 -0.12597 +EDGE3 894 944 1.41823 -0.000248059 -6.12806 -0.00209535 -0.00219695 0.00103773 +EDGE3 893 944 0.682728 12.2819 -6.23668 0.000806391 0.00851101 0.12351 +EDGE3 894 943 0.635955 -12.2841 -5.99608 -0.00467699 -0.00376475 -0.134576 +EDGE3 894 945 0.679318 12.2818 -6.23195 0.00118825 -0.00795286 0.12366 +EDGE3 895 945 1.40864 -0.012844 -6.13002 -0.00834935 0.00142604 0.00723521 +EDGE3 895 944 0.592132 -12.2793 -6.0035 0.00639186 0.00485144 -0.128133 +EDGE3 896 946 1.40423 0.0207073 -6.10975 0.00144999 0.00569358 -0.00660274 +EDGE3 895 946 0.639775 12.3113 -6.25143 0.00477225 -0.0166717 0.130281 +EDGE3 896 945 0.603417 -12.3056 -6.00374 0.0018931 0.0069759 -0.120542 +EDGE3 897 947 1.38251 0.006984 -6.13284 -0.00282607 -0.00411714 0.00133398 +EDGE3 896 947 0.63355 12.2813 -6.25267 0.00338005 -0.00808447 0.126239 +EDGE3 897 946 0.606659 -12.285 -6.00366 -0.00216654 -0.000355686 -0.128443 +EDGE3 898 948 1.3909 -0.0116025 -6.11676 -0.0124431 0.0111889 -0.0016828 +EDGE3 897 948 0.625937 12.3015 -6.25425 0.00845906 -0.00346932 0.12775 +EDGE3 898 947 0.593954 -12.302 -6.01007 -0.00119957 0.00456379 -0.121408 +EDGE3 899 949 1.37202 -0.0136238 -6.13328 0.000720631 -0.00133088 -0.0110404 +EDGE3 898 949 0.639001 12.3261 -6.24684 0.00899655 -0.00944377 0.126999 +EDGE3 899 948 0.576264 -12.3042 -6.00148 -0.00671951 -0.00920198 -0.127563 +EDGE3 900 950 1.37329 0.0095969 -6.14614 -0.000917323 0.00145675 0.00959225 +EDGE3 899 950 0.624442 12.3186 -6.2517 0.00197005 -0.00365961 0.130801 +EDGE3 900 949 0.569496 -12.3046 -6.01912 -0.00482615 -0.00351297 -0.123512 +EDGE3 900 951 0.619796 12.3117 -6.25467 -0.00105109 -0.000439623 0.120709 +EDGE3 901 951 1.34886 -0.0060602 -6.12723 -0.00299602 0.00186384 -0.00688798 +EDGE3 901 950 0.557983 -12.3053 -6.01626 0.00307654 -0.00394967 -0.121758 +EDGE3 901 952 0.610262 12.323 -6.24225 0.000972969 -0.00775554 0.12794 +EDGE3 902 952 1.35074 0.0162183 -6.11486 -0.00260742 -0.0049862 -0.00742132 +EDGE3 903 953 1.35723 0.00301418 -6.14143 0.00182306 0.00273582 0.00156668 +EDGE3 902 951 0.54796 -12.3023 -6.00424 -0.00246647 0.00114503 -0.131791 +EDGE3 903 952 0.552873 -12.3064 -5.9944 -0.00524744 0.00960853 -0.135848 +EDGE3 902 953 0.61223 12.3162 -6.25979 -0.00672935 -0.00430197 0.128348 +EDGE3 903 954 0.60383 12.3181 -6.26166 -0.0065822 -0.00835047 0.121902 +EDGE3 904 954 1.33441 0.0162009 -6.13698 0.00109401 0.0016154 -0.0038345 +EDGE3 905 955 1.3513 0.0106065 -6.15494 0.00488442 -0.0094876 -0.00170702 +EDGE3 904 953 0.53814 -12.3086 -6.02747 -0.00211598 -0.0022468 -0.123028 +EDGE3 905 954 0.53123 -12.3278 -6.02766 -0.0107462 -0.00592624 -0.117485 +EDGE3 904 955 0.57163 12.2975 -6.2396 0.00980072 -0.00526237 0.126709 +EDGE3 905 956 0.57085 12.3451 -6.25168 0.00801696 -0.00916345 0.130752 +EDGE3 906 956 1.31424 -0.0144378 -6.1428 -0.0020807 0.00134536 0.00486643 +EDGE3 907 957 1.31343 -0.00156147 -6.14747 -0.00119716 -0.00752041 0.00314761 +EDGE3 906 955 0.548212 -12.3312 -6.02117 4.07418e-05 -0.00493943 -0.128466 +EDGE3 906 957 0.578923 12.334 -6.27241 0.00850346 -0.00428564 0.127366 +EDGE3 907 956 0.52155 -12.3284 -6.01529 0.00439637 0.0090872 -0.122959 +EDGE3 907 958 0.587257 12.3351 -6.28879 -0.0073452 0.00174003 0.12443 +EDGE3 908 958 1.3068 -0.0112024 -6.14629 -0.00827801 -0.0035917 0.00613237 +EDGE3 909 959 1.29294 0.00703196 -6.13834 -0.00137629 0.000787664 0.00284521 +EDGE3 908 957 0.517327 -12.3224 -6.0128 0.00372952 -0.0013103 -0.128488 +EDGE3 909 958 0.499074 -12.3173 -6.00622 0.00687222 0.00377256 -0.128713 +EDGE3 908 959 0.561221 12.3405 -6.26909 -0.00783498 -0.0034372 0.125126 +EDGE3 909 960 0.543874 12.3251 -6.26349 -0.00129033 -0.00465335 0.122618 +EDGE3 910 960 1.29938 -0.00500983 -6.12778 0.0110455 -0.0105456 -0.00838596 +EDGE3 911 961 1.29606 0.00927738 -6.15944 -0.00297269 -0.00631774 0.00076435 +EDGE3 910 959 0.503782 -12.356 -6.00761 0.0115427 -0.00662942 -0.120722 +EDGE3 911 960 0.500549 -12.336 -6.03311 -0.00272687 -0.000448331 -0.125328 +EDGE3 910 961 0.540121 12.3474 -6.27953 -0.00455784 -0.00466248 0.124369 +EDGE3 912 962 1.27201 -0.0139277 -6.16434 -0.00170814 -0.00598426 -0.00128215 +EDGE3 911 962 0.523151 12.3318 -6.2762 -0.00423856 0.00469918 0.128898 +EDGE3 912 961 0.467285 -12.3407 -6.03466 0.000672055 0.00642302 -0.116371 +EDGE3 912 963 0.511173 12.3581 -6.28681 -0.000296436 -0.00588855 0.121275 +EDGE3 913 963 1.26538 0.0195631 -6.15703 -0.00100129 -0.000729118 0.00415576 +EDGE3 914 964 1.26889 0.00670503 -6.15493 -0.00159202 0.0103915 -0.00476241 +EDGE3 913 962 0.478175 -12.3578 -6.03211 0.00635982 0.00103811 -0.120296 +EDGE3 914 963 0.463203 -12.3527 -6.00585 0.000517109 0.000179433 -0.133705 +EDGE3 913 964 0.503917 12.3483 -6.25446 0.00148432 -0.00978965 0.118567 +EDGE3 915 965 1.24987 0.00820747 -6.15274 -0.00183071 -0.00662569 -0.00437037 +EDGE3 914 965 0.508178 12.3487 -6.2792 -0.00888262 0.00319929 0.128555 +EDGE3 915 964 0.446331 -12.3637 -6.02018 -0.00270743 -0.000991937 -0.125723 +EDGE3 915 966 0.499055 12.3504 -6.27269 0.00529931 0.00524925 0.114664 +EDGE3 916 966 1.25736 -0.00732422 -6.1452 -0.00660202 -0.00241542 0.00205075 +EDGE3 917 967 1.25239 0.0142705 -6.16553 -0.00645039 0.00803827 -0.00336245 +EDGE3 916 965 0.442367 -12.3339 -6.05349 -0.00639634 -0.00107273 -0.128076 +EDGE3 917 966 0.440082 -12.3385 -6.02526 -0.00114231 -0.000667393 -0.129356 +EDGE3 916 967 0.49644 12.3634 -6.27959 -0.00549495 0.00197265 0.120583 +EDGE3 918 968 1.23434 -0.00365065 -6.16906 -0.00496249 0.00236078 -0.000482333 +EDGE3 917 968 0.489728 12.3596 -6.27967 0.00142932 0.00719276 0.121319 +EDGE3 918 967 0.439968 -12.3541 -6.02642 -0.00216102 -0.00405389 -0.126493 +EDGE3 919 969 1.22516 0.00278926 -6.17017 -0.00117255 0.00412758 -0.000391844 +EDGE3 918 969 0.485572 12.3515 -6.26848 -0.000295214 -0.00118443 0.133584 +EDGE3 919 968 0.404469 -12.3773 -6.02557 -0.00795 -0.000211222 -0.133178 +EDGE3 919 970 0.467878 12.3758 -6.29101 0.0026752 -0.000834151 0.128323 +EDGE3 920 970 1.20835 -0.0131753 -6.16145 0.00161694 -0.001946 -0.000185535 +EDGE3 921 971 1.20561 0.0240297 -6.14075 0.0010094 0.00105745 0.00482321 +EDGE3 920 969 0.424364 -12.3529 -6.03515 0.0052887 0.00568446 -0.134672 +EDGE3 921 970 0.408734 -12.3598 -6.03674 -0.00649797 0.00384049 -0.117609 +EDGE3 920 971 0.452423 12.3788 -6.2915 0.00534066 0.00860607 0.128024 +EDGE3 921 972 0.446416 12.3764 -6.29522 0.0118329 0.00381232 0.132894 +EDGE3 922 972 1.20259 0.00355417 -6.15925 -0.00334537 -0.00697004 0.00234159 +EDGE3 923 973 1.18514 9.88396e-05 -6.18673 -0.000197293 -0.000985483 0.00192457 +EDGE3 922 971 0.38916 -12.3611 -6.04069 -0.000906461 -0.00416266 -0.133335 +EDGE3 922 973 0.448542 12.3739 -6.29604 0.00731807 -0.00754805 0.117346 +EDGE3 923 972 0.397423 -12.3939 -6.02388 0.000357669 -0.00288618 -0.124522 +EDGE3 924 974 1.18403 -0.00836346 -6.19252 0.0036563 -0.00194892 -0.000335919 +EDGE3 923 974 0.455072 12.3751 -6.29541 -0.00661486 0.00226548 0.122106 +EDGE3 924 973 0.377117 -12.3771 -6.04292 -0.00270048 0.0007927 -0.122845 +EDGE3 924 975 0.444272 12.3819 -6.30368 -0.00295162 0.00375906 0.116932 +EDGE3 925 975 1.17679 -0.00664939 -6.17047 -0.00158945 -0.0029452 0.00275905 +EDGE3 926 976 1.17834 -0.000155212 -6.15423 -0.00135211 -0.00577859 -0.00206245 +EDGE3 925 974 0.383113 -12.378 -6.04826 0.00562315 0.00519983 -0.125417 +EDGE3 925 976 0.414358 12.3858 -6.30084 0.00985756 0.000863773 0.132234 +EDGE3 926 975 0.375483 -12.3546 -6.04929 -0.000907777 -0.00740617 -0.132387 +EDGE3 926 977 0.409055 12.3843 -6.30332 -0.00763188 -0.00681301 0.125619 +EDGE3 927 977 1.16376 2.1267e-05 -6.1711 0.000326814 0.00847342 -0.00644074 +EDGE3 928 978 1.1642 0.000725468 -6.17526 0.00522955 0.00562953 -0.00244397 +EDGE3 927 976 0.346956 -12.3954 -6.05748 0.00301377 0.00143497 -0.131173 +EDGE3 928 977 0.36385 -12.3746 -6.0453 -0.00113535 -0.00898666 -0.132716 +EDGE3 927 978 0.404142 12.3725 -6.31458 0.0016967 -0.00086194 0.122392 +EDGE3 928 979 0.406518 12.3926 -6.30909 -0.00205739 -0.0115175 0.126615 +EDGE3 929 979 1.15249 -0.0141578 -6.17874 0.00392177 0.0114613 -0.00787066 +EDGE3 930 980 1.15316 0.00662657 -6.18451 0.000673186 -0.0002735 -0.00218742 +EDGE3 929 978 0.332521 -12.3791 -6.04325 -0.00654529 0.0032146 -0.125374 +EDGE3 930 979 0.34678 -12.39 -6.06228 0.00363697 0.00956232 -0.121316 +EDGE3 929 980 0.376984 12.3761 -6.31112 0.00508869 0.00266834 0.131037 +EDGE3 931 981 1.13178 0.00989899 -6.17257 -0.00547956 -0.00540132 -0.00153698 +EDGE3 930 981 0.378683 12.3852 -6.31768 0.0106281 0.00515017 0.141748 +EDGE3 931 980 0.332082 -12.4032 -6.04846 0.00554293 -0.00621236 -0.129254 +EDGE3 931 982 0.368375 12.4005 -6.29202 0.00408758 0.00390761 0.126541 +EDGE3 932 982 1.11534 -0.00120998 -6.16943 -0.00186869 0.00151602 0.00609478 +EDGE3 933 983 1.12554 0.0010008 -6.16528 -0.00278668 -0.0024285 -0.00607145 +EDGE3 932 981 0.314015 -12.3977 -6.05397 -0.00931639 -0.00117561 -0.128467 +EDGE3 933 982 0.319896 -12.3922 -6.05596 0.000163447 0.00580317 -0.13248 +EDGE3 932 983 0.35329 12.4024 -6.30786 0.00381123 0.00911388 0.119247 +EDGE3 933 984 0.348531 12.4103 -6.30853 0.00613441 0.00214688 0.125815 +EDGE3 934 984 1.10265 -0.00317828 -6.19798 -0.00289627 0.00138017 0.00781783 +EDGE3 935 985 1.09279 -0.00110114 -6.18044 -0.00478717 0.000300407 0.00500331 +EDGE3 934 983 0.314762 -12.3997 -6.06645 0.010192 -0.0103441 -0.119909 +EDGE3 934 985 0.349656 12.4159 -6.29735 0.00417574 0.000120967 0.122828 +EDGE3 935 984 0.305898 -12.4011 -6.06493 0.00502932 0.00278193 -0.127088 +EDGE3 936 986 1.09356 -0.00760128 -6.20371 0.00522372 0.000677498 -0.00291573 +EDGE3 935 986 0.338843 12.3824 -6.30497 0.00465162 -0.00268077 0.130236 +EDGE3 936 985 0.299258 -12.3861 -6.06812 -0.000948761 -0.00572699 -0.134244 +EDGE3 937 987 1.09011 0.00214327 -6.21089 0.00340262 0.000245568 -8.05977e-05 +EDGE3 936 987 0.322797 12.4271 -6.32068 -0.00793681 0.00650166 0.130631 +EDGE3 937 986 0.273276 -12.382 -6.06418 -0.00376226 0.00989404 -0.122372 +EDGE3 937 988 0.327626 12.4099 -6.31625 0.004722 -0.00168676 0.13254 +EDGE3 938 988 1.0772 0.00149656 -6.19341 0.000721342 0.00242046 -0.0111369 +EDGE3 938 987 0.282006 -12.4124 -6.07474 0.000401273 -0.00210328 -0.123923 +EDGE3 939 989 1.05859 0.0100306 -6.18469 0.00345259 0.00746671 0.00170097 +EDGE3 939 988 0.265342 -12.4167 -6.05214 -0.00523398 0.000627432 -0.122683 +EDGE3 938 989 0.299902 12.4205 -6.32466 -0.00429049 -0.0060912 0.134902 +EDGE3 940 990 1.05781 0.00739267 -6.19975 0.00015984 0.00686348 0.00627322 +EDGE3 939 990 0.310918 12.414 -6.31428 -0.00195948 -0.00357482 0.133624 +EDGE3 940 989 0.28778 -12.4056 -6.05775 -0.00376916 0.00302647 -0.134332 +EDGE3 941 991 1.0436 -0.0038343 -6.19714 0.00731681 0.00766539 0.00477858 +EDGE3 940 991 0.293219 12.4055 -6.33126 0.00915607 -0.00109939 0.119326 +EDGE3 941 990 0.266476 -12.4428 -6.07313 -0.0115682 -0.00165735 -0.12753 +EDGE3 942 992 1.04932 -0.0119403 -6.19012 0.00614943 -0.00957267 0.00640563 +EDGE3 941 992 0.28831 12.4034 -6.3047 -0.00171662 -3.57282e-05 0.12345 +EDGE3 942 991 0.247061 -12.4149 -6.06 0.00230425 0.00205061 -0.118095 +EDGE3 943 993 1.02358 -0.000630432 -6.20979 0.00191047 0.00276662 0.00273742 +EDGE3 942 993 0.269846 12.3999 -6.32157 -0.000529359 0.00724439 0.130329 +EDGE3 943 992 0.254435 -12.4292 -6.07158 0.0019671 0.00329468 -0.127201 +EDGE3 944 994 1.01583 0.00333199 -6.19533 -0.0101065 0.00658922 -0.00581701 +EDGE3 943 994 0.268617 12.4226 -6.31759 -0.00583432 -0.000550325 0.126998 +EDGE3 944 993 0.232943 -12.404 -6.08019 -0.0119207 4.58911e-05 -0.128864 +EDGE3 945 995 1.03632 -0.00630561 -6.19381 0.00195529 0.00326532 -0.00153914 +EDGE3 944 995 0.259965 12.4222 -6.33106 -0.0011013 0.00777909 0.118781 +EDGE3 945 994 0.233637 -12.4304 -6.06943 -0.000337167 0.00155628 -0.1164 +EDGE3 946 996 1.02151 0.00226066 -6.19641 -0.0102334 -0.000275929 0.00380689 +EDGE3 945 996 0.265137 12.4192 -6.31392 -0.00654312 0.00739586 0.128055 +EDGE3 946 995 0.212411 -12.4401 -6.08152 -0.00432938 -0.00150195 -0.125131 +EDGE3 947 997 0.998747 -0.000323848 -6.21549 0.002334 0.00469351 0.00299717 +EDGE3 946 997 0.237235 12.4187 -6.33066 -0.00558011 -0.00404293 0.137165 +EDGE3 947 996 0.228891 -12.4152 -6.08457 0.00186884 -0.00221371 -0.124625 +EDGE3 948 998 1.00376 0.00116976 -6.19593 0.00446083 0.000746661 -0.000748174 +EDGE3 947 998 0.241058 12.4373 -6.31868 -0.00598619 -0.00328714 0.132187 +EDGE3 948 997 0.196387 -12.4269 -6.08796 0.00673003 0.00220982 -0.130886 +EDGE3 949 999 1.00512 0.013779 -6.19131 -0.00565071 -0.00108759 -0.0105754 +EDGE3 948 999 0.225287 12.4377 -6.31977 0.000249408 -0.000821685 0.119942 +EDGE3 949 998 0.213248 -12.4309 -6.08001 -0.00222964 0.0023799 -0.126443 +EDGE3 950 1000 0.98102 -0.00306605 -6.19836 -0.00613493 -0.00135893 -0.0014606 +EDGE3 949 1000 0.232585 12.4419 -6.33436 0.00142009 -0.00242366 0.12687 +EDGE3 950 999 0.189062 -12.4256 -6.08281 0.00523343 0.00185522 -0.128949 +EDGE3 951 1001 0.975375 0.00768072 -6.22692 -0.00430789 0.00594 -0.000118962 +EDGE3 950 1001 0.208603 12.4269 -6.32333 -0.00536162 -0.00363218 0.119767 +EDGE3 951 1000 0.166275 -12.4273 -6.05729 0.00276332 0.000174576 -0.12653 +EDGE3 952 1002 0.987853 -0.00704614 -6.20494 0.0097229 -0.00393268 -0.00183978 +EDGE3 951 1002 0.194063 12.4326 -6.32394 0.00767435 0.00574661 0.127801 +EDGE3 952 1001 0.168852 -12.4225 -6.09701 0.000262297 -0.003593 -0.122415 +EDGE3 953 1003 0.950081 0.0153816 -6.20727 0.000254372 -0.00731587 -0.0060114 +EDGE3 952 1003 0.199526 12.4346 -6.32731 -0.000378253 -0.00606396 0.121514 +EDGE3 953 1002 0.150809 -12.4282 -6.07986 -0.000304953 0.00969106 -0.128889 +EDGE3 954 1004 0.946486 -0.000680319 -6.21236 0.00115896 -0.0057485 -0.000970213 +EDGE3 953 1004 0.193372 12.447 -6.33848 -0.00286072 -0.000892881 0.124768 +EDGE3 954 1003 0.155744 -12.4297 -6.07309 0.00249413 -0.00455836 -0.12696 +EDGE3 955 1005 0.940928 -0.00203069 -6.21673 -0.00125915 0.0107538 -0.00424114 +EDGE3 954 1005 0.186946 12.4365 -6.32083 0.0079441 -0.00673425 0.126728 +EDGE3 955 1004 0.154942 -12.4329 -6.08457 0.00488344 -0.00174657 -0.128409 +EDGE3 956 1006 0.933847 0.00238688 -6.21548 -0.0059931 -0.00201045 0.0125526 +EDGE3 955 1006 0.183827 12.4484 -6.32521 0.000647669 -0.00654096 0.132527 +EDGE3 956 1005 0.13535 -12.4563 -6.09488 -0.00585735 -0.00921591 -0.129447 +EDGE3 957 1007 0.930173 0.0161028 -6.22105 0.0106482 -0.000524441 -0.000184783 +EDGE3 956 1007 0.174524 12.4546 -6.35331 0.00175205 0.00228829 0.122308 +EDGE3 957 1006 0.138436 -12.445 -6.06686 0.00210672 0.0086721 -0.117886 +EDGE3 958 1008 0.903825 -0.00192976 -6.22001 0.00029388 -0.0107945 0.00477784 +EDGE3 957 1008 0.179146 12.4369 -6.32006 0.00279259 -0.0110523 0.126417 +EDGE3 958 1007 0.101163 -12.4464 -6.07986 0.000541385 0.00249453 -0.116964 +EDGE3 959 1009 0.906342 -0.00856364 -6.21543 0.00127277 0.00878754 0.00580358 +EDGE3 958 1009 0.156611 12.4367 -6.3438 0.00703469 0.00251908 0.118819 +EDGE3 959 1008 0.111431 -12.4608 -6.09641 0.00367663 -0.0063909 -0.129193 +EDGE3 960 1010 0.907487 0.000488393 -6.19627 0.00206818 -0.000659155 0.00141199 +EDGE3 959 1010 0.161393 12.4397 -6.32495 -0.00421346 0.00162753 0.130389 +EDGE3 960 1009 0.127172 -12.4682 -6.06094 -3.79076e-06 -0.00925412 -0.127221 +EDGE3 961 1011 0.899081 0.00612654 -6.21293 -0.00552186 0.00316975 0.00484587 +EDGE3 960 1011 0.105455 12.4696 -6.3236 0.00223434 0.00849022 0.126156 +EDGE3 961 1010 0.0863344 -12.4362 -6.08998 -0.0042649 0.00426816 -0.130004 +EDGE3 962 1012 0.886889 0.00758642 -6.22781 -0.00121303 -0.00688673 -0.00256044 +EDGE3 961 1012 0.120181 12.4637 -6.36714 -0.00111233 0.012226 0.125591 +EDGE3 962 1011 0.0890432 -12.457 -6.09793 0.00649252 -0.00472499 -0.120738 +EDGE3 963 1013 0.881525 -0.0108666 -6.23151 0.00177114 0.00108455 0.00388351 +EDGE3 962 1013 0.130425 12.4777 -6.34613 0.0051129 0.0026324 0.133182 +EDGE3 963 1012 0.0671111 -12.4561 -6.11101 0.00139044 -0.00446702 -0.1211 +EDGE3 964 1014 0.881881 3.53512e-05 -6.22672 -0.00241655 0.00535292 0.00104181 +EDGE3 963 1014 0.0881992 12.4713 -6.33989 0.00163842 -0.00282723 0.121401 +EDGE3 964 1013 0.061778 -12.4544 -6.1097 0.00249306 -0.00518575 -0.125997 +EDGE3 965 1015 0.870588 -0.0157077 -6.22349 0.00253831 -0.0033471 -0.00613663 +EDGE3 964 1015 0.112943 12.452 -6.35418 0.00028486 0.000485103 0.123035 +EDGE3 965 1014 0.0647916 -12.4532 -6.08749 0.00628512 0.000548888 -0.12328 +EDGE3 966 1016 0.851725 0.00343974 -6.23145 -0.00847509 0.00462879 -0.000283258 +EDGE3 965 1016 0.0861448 12.449 -6.34448 -0.00296327 0.000509518 0.129443 +EDGE3 966 1015 0.0540731 -12.4835 -6.10408 0.00285272 -0.00812065 -0.12139 +EDGE3 967 1017 0.856345 -0.00140981 -6.21976 -0.00026008 0.00130084 -0.00179775 +EDGE3 966 1017 0.0751446 12.4732 -6.34603 0.00130893 0.00616158 0.130975 +EDGE3 967 1016 0.0687291 -12.4645 -6.09054 -0.00121861 -0.00429264 -0.129576 +EDGE3 968 1018 0.849638 -0.00553813 -6.21589 -0.00381205 -0.00793486 -0.00568065 +EDGE3 967 1018 0.0739925 12.4723 -6.34859 0.00605877 -0.00338811 0.123831 +EDGE3 968 1017 0.0401351 -12.456 -6.11257 8.50867e-05 -0.00187582 -0.122856 +EDGE3 969 1019 0.845703 0.00285412 -6.21462 0.0110446 0.0029565 0.00390498 +EDGE3 968 1019 0.090834 12.4852 -6.3593 -0.00176008 -0.00483156 0.128593 +EDGE3 969 1018 0.034976 -12.477 -6.09197 0.00938761 -0.000768285 -0.128902 +EDGE3 970 1020 0.83051 -0.00272349 -6.22438 0.00479351 0.00386252 -0.00178471 +EDGE3 969 1020 0.0610178 12.4693 -6.35181 0.00273283 0.00886423 0.130709 +EDGE3 970 1019 0.0153774 -12.4634 -6.07613 -0.000465349 -0.00559529 -0.126142 +EDGE3 971 1021 0.817369 0.0143968 -6.24514 -0.000458342 0.00437675 0.0042899 +EDGE3 970 1021 0.0363313 12.4765 -6.35843 -0.00460936 -0.00502051 0.124341 +EDGE3 971 1020 0.0311528 -12.4776 -6.09635 0.00570905 -0.00841142 -0.126195 +EDGE3 972 1022 0.81075 0.00331246 -6.23729 0.000432404 0.00263212 -0.00147075 +EDGE3 971 1022 0.0244935 12.4547 -6.35744 0.00775972 0.000501019 0.125068 +EDGE3 972 1021 0.00365524 -12.4699 -6.10094 0.00241579 2.45102e-05 -0.122399 +EDGE3 973 1023 0.813347 0.00176729 -6.22425 0.00653377 -0.00687829 0.00555141 +EDGE3 972 1023 0.0165697 12.4622 -6.35939 0.00279259 0.00581969 0.12324 +EDGE3 973 1022 0.00342813 -12.4832 -6.08325 -0.00456874 -0.00979716 -0.131156 +EDGE3 974 1024 0.815219 0.0118716 -6.21697 -0.00343746 -0.00264425 -0.00255276 +EDGE3 974 1023 -0.0123738 -12.4877 -6.11063 0.00632502 0.00817007 -0.133285 +EDGE3 973 1024 0.0286498 12.5061 -6.35357 0.000873652 0.0114848 0.136197 +EDGE3 975 1025 0.764418 0.00138704 -6.23517 0.00125331 -0.00621262 0.00550948 +EDGE3 974 1025 0.0356864 12.4744 -6.36392 -0.002312 -0.00258022 0.123132 +EDGE3 975 1024 -0.0152994 -12.4505 -6.0972 -0.00174307 0.000861127 -0.12505 +EDGE3 976 1026 0.786564 -0.0127902 -6.23227 -0.00969193 0.00945945 0.00243047 +EDGE3 975 1026 0.0109601 12.4713 -6.34578 0.00188468 -0.00961783 0.127328 +EDGE3 976 1025 -0.0271344 -12.4707 -6.09649 0.000568799 -0.010896 -0.120939 +EDGE3 977 1027 0.764001 -0.00474215 -6.23829 0.0013005 -0.000156542 -0.000584371 +EDGE3 976 1027 -0.0103972 12.4807 -6.36363 -0.00432731 -0.00541724 0.132256 +EDGE3 977 1026 -0.0353862 -12.4924 -6.10864 0.00602444 -0.000226257 -0.120413 +EDGE3 978 1028 0.772794 -0.00992252 -6.22901 -0.00917619 -0.00153822 0.00513809 +EDGE3 978 1027 -0.0380511 -12.482 -6.11259 0.0012488 -0.00290825 -0.127314 +EDGE3 977 1028 -0.013139 12.4699 -6.36171 -0.00120376 -0.00168333 0.131217 +EDGE3 979 1029 0.759536 0.0132035 -6.25783 0.0105287 0.00481008 -0.00201089 +EDGE3 978 1029 -0.0280818 12.4854 -6.35505 0.00534858 -0.000818452 0.118082 +EDGE3 979 1028 -0.0334488 -12.4676 -6.09426 0.00200616 -0.00083474 -0.118689 +EDGE3 980 1030 0.736581 0.0176947 -6.23907 -0.00563987 -0.00866033 0.0021715 +EDGE3 979 1030 -0.00427572 12.479 -6.37696 0.000915469 -0.00708981 0.131256 +EDGE3 980 1029 -0.0345964 -12.4891 -6.10523 -0.00396398 0.00408186 -0.118732 +EDGE3 981 1031 0.751903 -0.00838249 -6.23848 -0.00584888 0.00630827 0.00106786 +EDGE3 980 1031 -0.0221652 12.4765 -6.35986 -0.00528576 -0.00106134 0.121417 +EDGE3 981 1030 -0.045977 -12.46 -6.12338 0.00224393 -0.00270947 -0.129517 +EDGE3 982 1032 0.73582 0.00498661 -6.23796 0.000451597 0.00121135 -0.0063392 +EDGE3 981 1032 -0.0485907 12.4821 -6.36222 -0.00528197 0.0027238 0.126636 +EDGE3 982 1031 -0.0563575 -12.47 -6.11338 -0.0104538 -0.00809705 -0.128747 +EDGE3 983 1033 0.722397 -0.00197137 -6.23714 -0.00165154 -0.00321876 -0.0018558 +EDGE3 982 1033 -0.0377629 12.5008 -6.36542 -0.00727788 -0.0155552 0.127888 +EDGE3 983 1032 -0.0548767 -12.4961 -6.11928 0.00709857 -0.00781062 -0.116993 +EDGE3 984 1034 0.726123 0.0167675 -6.24256 -0.010662 0.00169584 -0.00272517 +EDGE3 983 1034 -0.0457609 12.5036 -6.36618 0.00366015 -0.00338398 0.128765 +EDGE3 984 1033 -0.0834204 -12.499 -6.11644 0.0038669 -0.00177835 -0.129259 +EDGE3 985 1035 0.711576 0.0297586 -6.23777 0.00504254 8.86711e-05 -0.00181071 +EDGE3 984 1035 -0.0693881 12.4914 -6.37234 -0.00518308 0.00806861 0.119295 +EDGE3 985 1034 -0.0848856 -12.4897 -6.09056 0.000648842 -0.00588309 -0.13259 +EDGE3 986 1036 0.686904 0.00869389 -6.24361 -0.00747684 -0.00395844 -0.00662683 +EDGE3 985 1036 -0.0529557 12.4904 -6.35279 -0.00852332 0.00252901 0.125931 +EDGE3 986 1035 -0.0867065 -12.487 -6.13249 -0.00820808 4.3468e-05 -0.121558 +EDGE3 987 1037 0.695887 -0.00734272 -6.25551 -0.00501449 -0.000509627 0.00120932 +EDGE3 986 1037 -0.0696702 12.4848 -6.36072 -0.00306572 0.00632569 0.12058 +EDGE3 987 1036 -0.0994351 -12.4966 -6.12421 -0.00108775 0.00175917 -0.127472 +EDGE3 988 1038 0.701279 0.00704053 -6.23898 0.00661434 0.000931187 0.00342452 +EDGE3 987 1038 -0.0812596 12.503 -6.36863 0.0061399 0.00485606 0.124638 +EDGE3 988 1037 -0.113711 -12.4815 -6.11564 -3.33223e-05 -0.00464663 -0.122587 +EDGE3 989 1039 0.686689 -0.0019094 -6.25017 -0.0069805 -0.000595511 -0.00399799 +EDGE3 988 1039 -0.0866314 12.4955 -6.35568 -0.00249889 -0.00705797 0.123274 +EDGE3 989 1038 -0.116493 -12.4994 -6.12099 0.00291063 0.00682524 -0.124108 +EDGE3 990 1040 0.666889 0.00411714 -6.2503 -0.00265148 0.000459866 -0.00126887 +EDGE3 989 1040 -0.11478 12.4837 -6.3658 0.00173656 0.00558397 0.122541 +EDGE3 990 1039 -0.111651 -12.4974 -6.12395 -0.00332879 0.00543914 -0.12576 +EDGE3 990 1041 -0.105947 12.5168 -6.37371 -0.00525133 -0.00233592 0.123398 +EDGE3 991 1041 0.663029 0.0103897 -6.24071 -0.00362649 0.00568044 0.00334326 +EDGE3 992 1042 0.651015 0.00510679 -6.24883 0.00149873 0.0071623 -0.00663872 +EDGE3 991 1040 -0.139454 -12.5021 -6.11105 0.00110819 -0.005998 -0.124646 +EDGE3 992 1041 -0.127648 -12.5039 -6.11687 -0.00152544 -0.00198732 -0.123334 +EDGE3 991 1042 -0.11525 12.4887 -6.36796 0.00155542 -0.00262199 0.122935 +EDGE3 993 1043 0.639084 0.00180092 -6.24663 -0.00416522 -0.00182369 0.0018346 +EDGE3 992 1043 -0.121616 12.5032 -6.36786 0.00133817 0.0027953 0.128497 +EDGE3 993 1042 -0.139204 -12.4856 -6.13006 0.000833801 -0.00449236 -0.120986 +EDGE3 994 1044 0.624405 -0.000203848 -6.25704 -0.010349 -0.00591468 -0.0024043 +EDGE3 993 1044 -0.134905 12.5104 -6.38312 -0.00795368 -0.0018399 0.12749 +EDGE3 994 1043 -0.167308 -12.4984 -6.12636 -0.00100597 -0.00304658 -0.123693 +EDGE3 995 1045 0.630872 -0.000963202 -6.25075 0.00127655 -0.00261569 -0.00384713 +EDGE3 994 1045 -0.128148 12.502 -6.36727 0.00147246 -0.00205872 0.124576 +EDGE3 995 1044 -0.166231 -12.5013 -6.11632 0.00227439 0.0101222 -0.1341 +EDGE3 995 1046 -0.144957 12.4919 -6.37531 0.00349469 0.00249614 0.128982 +EDGE3 996 1046 0.637001 0.00638378 -6.2754 -0.00904298 -0.010392 0.00803121 +EDGE3 997 1047 0.614585 0.00510201 -6.24706 -0.00937562 0.00120399 0.00854015 +EDGE3 996 1045 -0.165641 -12.5047 -6.13066 0.00163576 -0.002318 -0.120639 +EDGE3 996 1047 -0.171014 12.5126 -6.37352 -0.00590674 0.00241845 0.122097 +EDGE3 997 1046 -0.185196 -12.5168 -6.15078 0.0012904 -0.00518797 -0.131865 +EDGE3 998 1048 0.602199 -0.0108784 -6.26008 0.00153997 -0.00234764 0.00892435 +EDGE3 997 1048 -0.160551 12.5201 -6.377 -0.000631774 -0.00598233 0.12043 +EDGE3 998 1047 -0.186443 -12.5106 -6.12934 0.00668855 0.00882906 -0.123751 +EDGE3 999 1049 0.607332 -0.0120566 -6.23938 0.00137675 -0.00483602 -0.00343843 +EDGE3 998 1049 -0.197888 12.5163 -6.38189 -0.0052321 0.00173962 0.129771 +EDGE3 999 1048 -0.181935 -12.5011 -6.13397 0.00410851 -0.00524469 -0.128643 +EDGE3 1000 1050 0.588093 -0.0148445 -6.26741 -0.00231877 -0.00100235 -0.0130073 +EDGE3 999 1050 -0.199047 12.5145 -6.3724 0.00492259 -0.00491484 0.122803 +EDGE3 1000 1049 -0.185762 -12.5051 -6.12252 0.0059023 -0.00303613 -0.129209 +EDGE3 1001 1051 0.576651 -0.0230348 -6.24744 0.00163988 -0.00371232 -0.00621163 +EDGE3 1000 1051 -0.190744 12.5071 -6.38772 -0.00761961 0.000404192 0.122363 +EDGE3 1001 1050 -0.214301 -12.5126 -6.13313 0.00646623 0.000543313 -0.123637 +EDGE3 1002 1052 0.583151 0.0160916 -6.23927 -0.00395168 0.000580358 -0.00446611 +EDGE3 1001 1052 -0.199188 12.5125 -6.39291 -0.00579728 -0.00311895 0.122716 +EDGE3 1002 1051 -0.219506 -12.5088 -6.1194 0.00620535 0.00369892 -0.132393 +EDGE3 1002 1053 -0.195822 12.5058 -6.40341 -0.00598364 0.000842441 0.121318 +EDGE3 1003 1053 0.545872 -0.0138138 -6.24532 0.002653 -0.00576536 0.00257887 +EDGE3 1004 1054 0.557681 0.018481 -6.24866 -0.00543603 0.00150283 0.00551855 +EDGE3 1003 1052 -0.233489 -12.5056 -6.12649 -0.00438419 0.0066131 -0.127839 +EDGE3 1004 1053 -0.22399 -12.5041 -6.14365 -0.00713551 -0.00379206 -0.127584 +EDGE3 1003 1054 -0.21314 12.5051 -6.40255 0.000985135 0.00195386 0.127411 +EDGE3 1005 1055 0.559756 0.00319804 -6.25159 0.00166463 -0.00546423 0.00351203 +EDGE3 1004 1055 -0.220853 12.529 -6.37933 0.000678529 -0.00895906 0.118821 +EDGE3 1005 1054 -0.250759 -12.5088 -6.13133 0.00505392 0.00319929 -0.121046 +EDGE3 1006 1056 0.548373 -0.000856317 -6.24571 -0.00575078 0.00921525 -0.00712818 +EDGE3 1005 1056 -0.226918 12.4862 -6.38549 0.000862255 0.00682133 0.139088 +EDGE3 1006 1055 -0.237524 -12.5277 -6.13865 0.000106748 -0.00917776 -0.126228 +EDGE3 1007 1057 0.536273 0.0158555 -6.24922 0.00360437 0.000913854 -0.00510339 +EDGE3 1006 1057 -0.22783 12.5045 -6.38718 -0.00314142 0.000183785 0.134188 +EDGE3 1008 1058 0.52877 0.0132027 -6.25477 -0.000238392 -0.00466798 -0.00515544 +EDGE3 1007 1056 -0.270363 -12.5179 -6.12874 0.00464371 0.00404607 -0.119477 +EDGE3 1007 1058 -0.25221 12.508 -6.39139 0.00473052 0.00561593 0.119774 +EDGE3 1008 1057 -0.277897 -12.5259 -6.13128 0.00801065 -0.00276281 -0.128398 +EDGE3 1009 1059 0.506995 -0.00850315 -6.28101 0.00558712 -0.00138337 -0.000697701 +EDGE3 1008 1059 -0.2426 12.5065 -6.39821 0.00158702 -0.00567758 0.120517 +EDGE3 1009 1058 -0.261819 -12.5165 -6.11328 -0.009556 -0.00487809 -0.12106 +EDGE3 1010 1060 0.512187 0.00380349 -6.27106 0.00575713 0.00574692 -0.0027486 +EDGE3 1009 1060 -0.262489 12.5225 -6.38027 -0.00650878 0.00315928 0.12692 +EDGE3 1010 1059 -0.262447 -12.5249 -6.14288 0.000213439 0.00106896 -0.123348 +EDGE3 1011 1061 0.507848 -0.0132595 -6.25333 -0.00497433 0.00022107 0.00169572 +EDGE3 1010 1061 -0.276878 12.5253 -6.38623 0.000493188 -0.00062713 0.120933 +EDGE3 1011 1060 -0.302541 -12.5237 -6.13515 -0.00021765 0.00386733 -0.123577 +EDGE3 1012 1062 0.495755 -0.00342218 -6.26372 0.00328661 -0.0066673 -0.000715521 +EDGE3 1011 1062 -0.276972 12.523 -6.38398 -0.00306386 0.00376326 0.120178 +EDGE3 1012 1061 -0.287706 -12.5064 -6.13656 -0.00316163 -0.00273037 -0.123854 +EDGE3 1013 1063 0.486013 0.0201915 -6.2588 -0.00705937 -0.00536856 -0.0024275 +EDGE3 1012 1063 -0.280634 12.5144 -6.38975 0.00153201 0.00372571 0.128677 +EDGE3 1014 1064 0.482747 0.00405779 -6.25622 0.00321114 0.00128575 0.00041016 +EDGE3 1013 1062 -0.300117 -12.5166 -6.148 0.00104096 0.00125921 -0.125917 +EDGE3 1013 1064 -0.299535 12.5097 -6.38625 -0.0088264 0.00474337 0.133462 +EDGE3 1014 1063 -0.298692 -12.5233 -6.1392 -0.00924332 -0.000568681 -0.123759 +EDGE3 1015 1065 0.47199 -0.00530056 -6.2637 -0.00522823 0.00148066 -0.00435683 +EDGE3 1014 1065 -0.308605 12.5192 -6.3829 -0.00670152 -0.00147826 0.129165 +EDGE3 1016 1066 0.44431 0.00287273 -6.26808 -0.00501712 -0.00289772 0.000776499 +EDGE3 1015 1064 -0.319473 -12.5018 -6.12574 -0.00325072 0.00140551 -0.126934 +EDGE3 1015 1066 -0.301862 12.5248 -6.39567 -0.00113133 0.00435017 0.125263 +EDGE3 1016 1065 -0.319821 -12.5254 -6.14241 -0.00434756 -0.00243053 -0.128796 +EDGE3 1017 1067 0.464498 0.00829791 -6.25089 -0.00514171 0.00147153 -0.00499085 +EDGE3 1016 1067 -0.310813 12.5415 -6.39103 0.01152 -0.00207167 0.127184 +EDGE3 1017 1066 -0.351802 -12.5211 -6.14126 -0.000203881 -0.000846365 -0.122255 +EDGE3 1018 1068 0.44746 -0.000470335 -6.28817 0.00393862 0.00316305 -0.012556 +EDGE3 1017 1068 -0.31083 12.5006 -6.37347 0.00533918 -0.000463818 0.133204 +EDGE3 1019 1069 0.446319 0.0142445 -6.26833 0.00434445 0.00640258 0.00746184 +EDGE3 1018 1067 -0.340905 -12.5207 -6.14163 0.00626786 -0.00631899 -0.12472 +EDGE3 1019 1068 -0.351197 -12.5189 -6.14598 0.00144921 -0.00373631 -0.127866 +EDGE3 1018 1069 -0.320945 12.5284 -6.38844 -0.00678782 0.001441 0.123295 +EDGE3 1020 1070 0.427504 0.0126791 -6.26717 -0.00110486 -0.00600884 0.00151282 +EDGE3 1019 1070 -0.338156 12.5276 -6.38908 -0.00400373 -0.000136708 0.129281 +EDGE3 1020 1069 -0.362348 -12.534 -6.1418 -0.00161087 -0.00410936 -0.123078 +EDGE3 1021 1071 0.425285 -0.0075892 -6.2624 0.00177453 0.00235862 -0.00175729 +EDGE3 1020 1071 -0.35949 12.5254 -6.38792 -0.00455641 0.00330665 0.120728 +EDGE3 1021 1070 -0.372646 -12.538 -6.11628 0.0145607 0.00172648 -0.133737 +EDGE3 1022 1072 0.40939 -0.0108033 -6.27539 0.000631527 -0.00410589 -0.00448087 +EDGE3 1021 1072 -0.385797 12.5414 -6.39678 -0.00205942 -0.00155908 0.120386 +EDGE3 1022 1071 -0.378597 -12.5527 -6.14593 -0.00680235 -0.00126295 -0.116706 +EDGE3 1023 1073 0.404221 0.00579676 -6.27893 -0.00495481 -0.00184616 -0.00522322 +EDGE3 1022 1073 -0.379647 12.5247 -6.3939 0.00434515 0.000411133 0.136366 +EDGE3 1024 1074 0.391503 -0.0138821 -6.26853 0.00194373 0.00817654 -0.00384202 +EDGE3 1023 1072 -0.384374 -12.5484 -6.14782 -0.00302179 0.000226253 -0.12822 +EDGE3 1023 1074 -0.387382 12.5268 -6.39582 -0.00215746 -0.00797828 0.120408 +EDGE3 1024 1073 -0.404685 -12.5148 -6.12644 0.000971984 0.00606791 -0.122076 +EDGE3 1025 1075 0.406576 0.00623958 -6.2726 0.000118843 -0.00161025 0.000426346 +EDGE3 1024 1075 -0.386386 12.5168 -6.3935 -0.00273871 -0.000416093 0.12274 +EDGE3 1025 1074 -0.380451 -12.5189 -6.14221 -0.000935182 0.000587987 -0.126968 +EDGE3 1026 1076 0.387173 0.0222664 -6.26207 -0.00446999 0.00661585 -0.0162995 +EDGE3 1025 1076 -0.39731 12.5183 -6.40298 0.00313331 -0.00142002 0.113178 +EDGE3 1027 1077 0.381764 0.0177537 -6.27712 -0.00473262 0.00518458 -0.00172216 +EDGE3 1026 1075 -0.398159 -12.5313 -6.13373 0.000320591 -0.00223746 -0.12076 +EDGE3 1026 1077 -0.404623 12.5393 -6.39946 -0.00703611 -0.00506246 0.129275 +EDGE3 1027 1076 -0.421867 -12.5319 -6.12938 0.00080054 2.16396e-06 -0.12071 +EDGE3 1028 1078 0.364941 -0.00682327 -6.26263 -0.00222127 0.00361208 -0.00277724 +EDGE3 1027 1078 -0.402639 12.5019 -6.38842 0.00572882 -0.00113922 0.112137 +EDGE3 1028 1077 -0.423337 -12.5223 -6.12316 0.000953783 -0.00698766 -0.124035 +EDGE3 1029 1079 0.36205 0.000555717 -6.26377 0.00103909 0.00292397 0.0018167 +EDGE3 1028 1079 -0.416218 12.5104 -6.39309 0.00149309 0.00678344 0.127842 +EDGE3 1030 1080 0.354122 0.000557097 -6.26988 0.00610043 0.00512122 0.00121343 +EDGE3 1029 1078 -0.415947 -12.5206 -6.14146 0.00641839 -0.00368707 -0.127464 +EDGE3 1029 1080 -0.425649 12.5332 -6.41522 -0.00691993 0.00747921 0.125989 +EDGE3 1030 1079 -0.444427 -12.5228 -6.1564 0.00385524 -0.000270493 -0.131101 +EDGE3 1031 1081 0.323141 -0.00174244 -6.28445 0.00585087 0.00274641 -0.0026642 +EDGE3 1030 1081 -0.431584 12.5317 -6.38935 -0.00519359 0.00404818 0.122387 +EDGE3 1031 1080 -0.43128 -12.5365 -6.17378 0.00686573 -0.00112914 -0.125687 +EDGE3 1032 1082 0.343282 -0.00258827 -6.27217 0.00785878 0.00193116 0.00194795 +EDGE3 1031 1082 -0.450662 12.5164 -6.41051 0.00293462 -0.0076397 0.126313 +EDGE3 1032 1081 -0.451586 -12.5083 -6.14878 0.00271711 0.00320522 -0.126127 +EDGE3 1033 1083 0.33372 -0.0235262 -6.26866 0.00163728 0.00428167 0.00456563 +EDGE3 1032 1083 -0.44836 12.523 -6.40191 -0.00887786 -0.0102621 0.118729 +EDGE3 1033 1082 -0.470893 -12.5342 -6.14275 -0.00111154 0.00349921 -0.130402 +EDGE3 1034 1084 0.317439 0.00428264 -6.27274 0.00174271 0.00149354 -0.00434332 +EDGE3 1033 1084 -0.437451 12.5304 -6.38576 0.00154293 0.00119669 0.127318 +EDGE3 1034 1083 -0.446281 -12.5253 -6.16127 -0.00440954 0.00272367 -0.126248 +EDGE3 1035 1085 0.298068 0.00256139 -6.29128 -0.00455709 0.00258623 0.00892775 +EDGE3 1034 1085 -0.460094 12.5377 -6.39615 -0.00387592 0.0072131 0.134939 +EDGE3 1035 1084 -0.472045 -12.525 -6.14212 0.00525149 0.00604261 -0.121385 +EDGE3 1036 1086 0.298859 0.00220704 -6.25972 -0.011724 0.00497854 -0.00716465 +EDGE3 1035 1086 -0.47334 12.5329 -6.40778 -0.000835223 0.0012579 0.12997 +EDGE3 1036 1085 -0.484904 -12.5176 -6.14107 0.00506844 0.00237413 -0.121361 +EDGE3 1037 1087 0.285679 0.0104881 -6.25979 -0.00472771 0.00425943 -0.00251493 +EDGE3 1036 1087 -0.481177 12.5171 -6.39547 -0.00100882 0.0012827 0.117663 +EDGE3 1037 1086 -0.506808 -12.5305 -6.15569 0.00760808 0.00539201 -0.120935 +EDGE3 1038 1088 0.297579 -0.00682341 -6.26887 -0.00328675 8.67593e-05 -0.000967068 +EDGE3 1037 1088 -0.495501 12.5242 -6.40356 0.00743762 -0.00333221 0.12703 +EDGE3 1038 1087 -0.480813 -12.531 -6.14404 0.00152894 -0.0025846 -0.122954 +EDGE3 1039 1089 0.278612 -0.0134488 -6.26645 0.00664905 -0.00347998 0.00264618 +EDGE3 1038 1089 -0.504149 12.53 -6.40451 0.00469796 0.00639568 0.125592 +EDGE3 1039 1088 -0.500858 -12.5452 -6.14331 0.00632373 -0.00292675 -0.134841 +EDGE3 1040 1090 0.270624 -0.00372858 -6.27733 -0.00873867 0.0039414 0.00433455 +EDGE3 1039 1090 -0.505859 12.5401 -6.40265 -0.00274282 -0.00663094 0.127929 +EDGE3 1040 1089 -0.516525 -12.5457 -6.14969 0.00670202 -0.00319466 -0.12781 +EDGE3 1041 1091 0.272474 -0.00369477 -6.2653 -0.00120342 0.00222899 0.0011086 +EDGE3 1040 1091 -0.493425 12.5347 -6.38473 -0.00185871 0.0010592 0.131945 +EDGE3 1041 1090 -0.524219 -12.5313 -6.15082 0.0104448 -0.00801705 -0.120278 +EDGE3 1042 1092 0.265304 0.000762534 -6.27577 0.00210914 -0.00142372 -0.00471483 +EDGE3 1041 1092 -0.508479 12.5344 -6.41172 -0.000427451 -0.00670079 0.125384 +EDGE3 1042 1091 -0.531107 -12.5259 -6.12991 -0.00620666 0.00161012 -0.123038 +EDGE3 1043 1093 0.255221 -0.0114643 -6.29279 -0.000814872 0.00217647 0.0102762 +EDGE3 1042 1093 -0.522997 12.5472 -6.40753 0.00341459 -0.00497783 0.131574 +EDGE3 1043 1092 -0.537352 -12.5338 -6.14354 0.00562279 0.00687441 -0.124954 +EDGE3 1044 1094 0.231708 -0.0137804 -6.27151 0.0033834 0.00410246 0.00296196 +EDGE3 1043 1094 -0.53021 12.5404 -6.39912 0.000834043 -0.00393727 0.131139 +EDGE3 1044 1093 -0.537188 -12.55 -6.14679 0.0080184 0.00161169 -0.121808 +EDGE3 1045 1095 0.253302 -0.00834 -6.27605 -0.00672171 -0.00236143 -0.0123973 +EDGE3 1044 1095 -0.537043 12.5343 -6.38888 0.0055114 -0.000246843 0.115042 +EDGE3 1045 1094 -0.52802 -12.5492 -6.13887 0.00340438 0.00233629 -0.129119 +EDGE3 1046 1096 0.236117 0.00644192 -6.2777 -0.00366992 0.0051391 -0.00765547 +EDGE3 1045 1096 -0.568126 12.5357 -6.39896 0.00556515 -0.00362158 0.126788 +EDGE3 1046 1095 -0.554654 -12.5286 -6.16316 0.000297155 -0.00156953 -0.122061 +EDGE3 1047 1097 0.215826 0.0027056 -6.29331 0.00420513 -0.00916484 0.00529622 +EDGE3 1047 1096 -0.575023 -12.5387 -6.14175 -0.00218035 -0.000235105 -0.126417 +EDGE3 1046 1097 -0.570179 12.5379 -6.40405 -0.00543667 -0.00178978 0.123264 +EDGE3 1048 1098 0.215206 -0.00976241 -6.27914 -0.00153683 -0.000180451 -0.00335491 +EDGE3 1047 1098 -0.564887 12.5387 -6.38683 0.000722098 -0.00234415 0.125471 +EDGE3 1048 1097 -0.58808 -12.5472 -6.16781 -0.0096506 0.00195949 -0.128922 +EDGE3 1049 1099 0.213304 -0.00205135 -6.2654 0.00422135 -0.00499441 -0.00743441 +EDGE3 1048 1099 -0.573358 12.5255 -6.40817 0.00559041 0.00313199 0.132105 +EDGE3 1049 1098 -0.584573 -12.5558 -6.15662 -0.000590938 0.00193715 -0.121993 +EDGE3 1050 1100 0.196842 -0.00878122 -6.26398 0.00502871 -0.00912132 -0.00387076 +EDGE3 1050 1099 -0.596702 -12.5365 -6.15971 -0.00321903 0.000360408 -0.123481 +EDGE3 1049 1100 -0.58747 12.5334 -6.40297 0.00511473 0.00303579 0.13453 +EDGE3 1051 1101 0.186447 0.00807411 -6.27847 -0.00775935 0.00481857 -0.00328007 +EDGE3 1050 1101 -0.605399 12.5384 -6.4021 -0.00267565 -0.00393191 0.128833 +EDGE3 1051 1100 -0.6121 -12.5372 -6.15949 -0.00136945 0.00689434 -0.129984 +EDGE3 1052 1102 0.181803 0.00180035 -6.27212 -0.00174061 -0.00486135 0.00449928 +EDGE3 1051 1102 -0.591592 12.5322 -6.40781 0.0063865 -0.00166408 0.121012 +EDGE3 1052 1101 -0.604733 -12.522 -6.1555 0.00351985 0.00652907 -0.122691 +EDGE3 1053 1103 0.178218 -0.000337323 -6.27229 0.000536779 0.00684484 -0.0021648 +EDGE3 1052 1103 -0.585298 12.5264 -6.41144 0.00103311 0.00827947 0.124093 +EDGE3 1053 1102 -0.614128 -12.5375 -6.15385 0.000120277 0.00737525 -0.120787 +EDGE3 1054 1104 0.150053 -0.00540746 -6.28945 0.00468344 -0.00733821 -0.00120659 +EDGE3 1053 1104 -0.610268 12.5227 -6.38996 -0.00127093 -0.00741288 0.12665 +EDGE3 1054 1103 -0.628142 -12.5387 -6.15311 0.00627335 -0.00557564 -0.12232 +EDGE3 1055 1105 0.157036 0.00225103 -6.2568 -0.0108907 -0.00280618 -0.00584148 +EDGE3 1054 1105 -0.616292 12.5246 -6.39907 -0.0030841 -0.0093312 0.131113 +EDGE3 1055 1104 -0.625805 -12.5288 -6.14966 0.00199975 -0.00412772 -0.121731 +EDGE3 1056 1106 0.158603 -0.00407588 -6.28066 0.00140752 -0.00675594 -0.00570593 +EDGE3 1055 1106 -0.632382 12.5321 -6.39424 0.00608578 0.000663047 0.129288 +EDGE3 1056 1105 -0.656775 -12.5298 -6.15814 -5.40591e-05 0.00682029 -0.129037 +EDGE3 1057 1107 0.151505 -0.00415746 -6.27098 -0.00125841 0.0042056 -0.00464014 +EDGE3 1057 1106 -0.634193 -12.5425 -6.13072 0.00699202 -0.000568379 -0.120617 +EDGE3 1056 1107 -0.630261 12.5235 -6.41326 -0.00123813 -0.00416774 0.118434 +EDGE3 1058 1108 0.130147 0.00137597 -6.29459 0.0016229 0.00480329 0.00144662 +EDGE3 1057 1108 -0.627731 12.53 -6.40611 0.000434816 -0.00558811 0.122298 +EDGE3 1058 1107 -0.634353 -12.53 -6.15021 0.00082961 -0.000214506 -0.12332 +EDGE3 1059 1109 0.139252 -4.85242e-05 -6.28016 -0.00286651 -0.00129127 -0.00448589 +EDGE3 1058 1109 -0.656046 12.5204 -6.40345 0.00187218 -0.00634739 0.130203 +EDGE3 1059 1108 -0.666997 -12.545 -6.15648 0.00273863 -0.00101674 -0.116751 +EDGE3 1060 1110 0.126571 0.00593311 -6.26836 -0.000589104 0.00432292 -0.00938123 +EDGE3 1059 1110 -0.670749 12.5307 -6.40041 0.009735 0.000874088 0.126952 +EDGE3 1060 1109 -0.679967 -12.5531 -6.1694 0.00242599 -0.0056071 -0.13027 +EDGE3 1061 1111 0.118784 -0.00889716 -6.29441 -0.000169401 -0.0113408 -0.000393405 +EDGE3 1060 1111 -0.67643 12.5292 -6.40984 0.000426927 -0.00351018 0.114537 +EDGE3 1061 1110 -0.674807 -12.5157 -6.16288 0.00871761 0.00550555 -0.124798 +EDGE3 1062 1112 0.105382 0.0180988 -6.29827 -0.0108443 -0.000692556 -0.00726544 +EDGE3 1061 1112 -0.671611 12.5378 -6.39889 0.00392201 -0.000251143 0.134209 +EDGE3 1062 1111 -0.685911 -12.536 -6.15941 -0.00755406 -0.000760265 -0.122366 +EDGE3 1063 1113 0.0881616 0.0224931 -6.30795 0.000253918 -0.00933923 -0.00344978 +EDGE3 1062 1113 -0.680954 12.5197 -6.41158 0.00690387 -0.00394083 0.12975 +EDGE3 1063 1112 -0.693239 -12.5362 -6.18083 -0.00753381 -0.00438918 -0.130141 +EDGE3 1064 1114 0.101602 0.00307337 -6.2694 -0.00659361 0.00427556 0.00404577 +EDGE3 1063 1114 -0.691795 12.5247 -6.42841 -0.00172994 -0.00555966 0.132909 +EDGE3 1064 1113 -0.698631 -12.5388 -6.1615 -0.00163118 -0.001496 -0.119288 +EDGE3 1065 1115 0.0793443 -0.00219868 -6.27819 -0.00167051 -0.00360164 0.00386995 +EDGE3 1064 1115 -0.699234 12.5191 -6.40585 0.00136968 -0.00314091 0.126146 +EDGE3 1065 1114 -0.70301 -12.5239 -6.1635 0.00371223 -0.0161884 -0.128878 +EDGE3 1066 1116 0.0673886 -0.00413551 -6.27449 -0.00228833 -0.00444908 0.0044582 +EDGE3 1065 1116 -0.724344 12.5431 -6.39829 0.00136248 -0.00528446 0.124388 +EDGE3 1066 1115 -0.714459 -12.5228 -6.15068 0.00763655 0.00356848 -0.116576 +EDGE3 1067 1117 0.0692146 0.0115431 -6.28964 -0.000991295 -0.00243402 0.00191106 +EDGE3 1066 1117 -0.725343 12.5329 -6.39238 0.00329202 -0.00198851 0.123636 +EDGE3 1067 1116 -0.698362 -12.5378 -6.15465 -0.00108499 -0.00583977 -0.127373 +EDGE3 1068 1118 0.0591034 -0.00439366 -6.28936 0.00178434 -0.000877614 -0.000206415 +EDGE3 1067 1118 -0.721072 12.5356 -6.41317 -0.00747704 0.000238211 0.124507 +EDGE3 1068 1117 -0.724828 -12.5482 -6.14913 0.00194813 0.00398907 -0.122854 +EDGE3 1069 1119 0.0513294 -0.0144649 -6.28754 -0.0066207 0.00399452 -0.00697591 +EDGE3 1068 1119 -0.73771 12.5209 -6.38839 0.00947757 0.00133226 0.124942 +EDGE3 1069 1118 -0.731358 -12.5352 -6.15417 -0.00491621 0.00261442 -0.117228 +EDGE3 1070 1120 0.0610248 -0.020333 -6.28211 0.00181477 -0.000250336 -0.00246901 +EDGE3 1069 1120 -0.726403 12.5144 -6.38889 -0.00744381 0.00560057 0.120091 +EDGE3 1070 1119 -0.733996 -12.5488 -6.15235 -0.0106787 0.00343041 -0.128956 +EDGE3 1071 1121 0.0459769 -0.0078815 -6.2772 0.000832492 0.00453685 -0.00967456 +EDGE3 1070 1121 -0.738711 12.5276 -6.40419 0.00876837 -0.00217113 0.122835 +EDGE3 1071 1120 -0.75472 -12.5294 -6.15331 -0.00576202 -0.000252038 -0.12591 +EDGE3 1072 1122 0.0254335 0.0170265 -6.26833 0.00100882 0.00122348 0.000899456 +EDGE3 1071 1122 -0.756057 12.5231 -6.39586 0.00412678 -0.00554809 0.125329 +EDGE3 1072 1121 -0.781539 -12.5095 -6.16597 -0.00225318 -0.00497592 -0.131812 +EDGE3 1073 1123 -0.00779686 0.0127342 -6.28762 -0.00181948 0.00980043 -0.000891788 +EDGE3 1072 1123 -0.768888 12.535 -6.40935 -0.00214086 -0.000726923 0.127879 +EDGE3 1073 1122 -0.765813 -12.5358 -6.16614 0.00258391 0.00376022 -0.125167 +EDGE3 1074 1124 0.00760943 0.00885651 -6.27791 -6.29263e-05 -0.00288755 -0.00255675 +EDGE3 1073 1124 -0.774086 12.5283 -6.40037 -0.000684656 -0.00204612 0.120947 +EDGE3 1074 1123 -0.774678 -12.5189 -6.14477 0.00597172 -0.000830503 -0.130335 +EDGE3 1075 1125 -0.0114419 -0.0104234 -6.27668 -0.00358681 -0.00433574 -0.00303269 +EDGE3 1074 1125 -0.780464 12.5266 -6.41603 -0.00282593 0.00522903 0.128835 +EDGE3 1075 1124 -0.776114 -12.5351 -6.14075 -0.00541994 0.00666464 -0.127735 +EDGE3 1076 1126 -0.00638068 0.00804933 -6.28179 -0.00262233 0.00523934 0.0049855 +EDGE3 1075 1126 -0.791402 12.523 -6.39566 0.00216761 -0.00189525 0.126251 +EDGE3 1076 1125 -0.777749 -12.5238 -6.15664 0.00845533 -0.00576496 -0.123574 +EDGE3 1077 1127 -0.00783565 0.00656201 -6.27246 0.00362951 -5.40804e-06 0.0128864 +EDGE3 1076 1127 -0.799878 12.5316 -6.40765 0.00281899 0.000215755 0.128125 +EDGE3 1077 1126 -0.798945 -12.5205 -6.15536 0.00680282 0.0107364 -0.114397 +EDGE3 1078 1128 -0.00407535 0.0175364 -6.28299 -0.000764176 -0.00386429 0.000772284 +EDGE3 1077 1128 -0.801422 12.5271 -6.43103 -0.00792257 0.00353903 0.117007 +EDGE3 1078 1127 -0.805814 -12.5215 -6.16464 0.00218513 0.00335927 -0.126909 +EDGE3 1079 1129 -0.0434275 0.00298766 -6.28523 0.00390387 -0.00561875 -0.00984356 +EDGE3 1078 1129 -0.814488 12.5314 -6.41883 -0.00126625 0.00332843 0.125542 +EDGE3 1079 1128 -0.814984 -12.5133 -6.15136 0.00485604 0.0062283 -0.124007 +EDGE3 1080 1130 -0.045893 -0.0118615 -6.26462 0.00396884 0.00240737 0.00349117 +EDGE3 1079 1130 -0.821212 12.5163 -6.40514 -0.00152007 -0.00215704 0.12986 +EDGE3 1080 1129 -0.814512 -12.5379 -6.1463 -0.00110188 0.00237988 -0.127855 +EDGE3 1081 1131 -0.0468393 -0.0163697 -6.30317 -0.00785785 -0.00556961 -0.00246851 +EDGE3 1080 1131 -0.832953 12.5325 -6.39371 -0.00589152 -0.00633728 0.130426 +EDGE3 1081 1130 -0.825406 -12.5183 -6.16685 0.00327162 0.00224276 -0.127414 +EDGE3 1082 1132 -0.0459218 0.00443567 -6.28107 -0.000253152 -0.000406939 -0.00594454 +EDGE3 1081 1132 -0.834901 12.5315 -6.41685 -0.00139795 0.00360313 0.126465 +EDGE3 1082 1131 -0.832122 -12.5216 -6.15362 -0.00664387 -0.0105139 -0.126425 +EDGE3 1083 1133 -0.0698737 -0.0156165 -6.27997 -0.0069158 0.000102981 -0.0122023 +EDGE3 1082 1133 -0.837836 12.5064 -6.40685 0.00226147 -0.00408177 0.124737 +EDGE3 1083 1132 -0.868362 -12.5218 -6.12821 0.000828495 -0.00682059 -0.13481 +EDGE3 1084 1134 -0.0783844 -0.00377666 -6.27044 0.00884074 0.00450091 0.0114331 +EDGE3 1083 1134 -0.853754 12.5204 -6.41936 0.00309048 -0.000604733 0.133968 +EDGE3 1084 1133 -0.85316 -12.519 -6.14943 0.0013359 0.00375342 -0.120594 +EDGE3 1085 1135 -0.0778737 0.00462773 -6.27116 -0.00677234 -0.00454022 0.00144336 +EDGE3 1084 1135 -0.868098 12.5108 -6.409 -0.00701461 -0.00268314 0.123658 +EDGE3 1085 1134 -0.857416 -12.5345 -6.1496 0.00312789 -0.00519318 -0.130011 +EDGE3 1086 1136 -0.0975345 -0.0027181 -6.27561 -0.00257942 0.000305097 0.00153199 +EDGE3 1085 1136 -0.865826 12.5104 -6.40781 0.00389424 0.00265239 0.127288 +EDGE3 1086 1135 -0.876613 -12.5188 -6.16435 0.00317809 -0.00790368 -0.126882 +EDGE3 1087 1137 -0.096935 0.00655381 -6.28275 0.00208458 0.0104077 -0.00184949 +EDGE3 1086 1137 -0.862719 12.5124 -6.40403 -0.00347192 -0.000758677 0.120583 +EDGE3 1087 1136 -0.860165 -12.5213 -6.14097 -0.00582715 0.00498118 -0.125193 +EDGE3 1088 1138 -0.109095 0.00141071 -6.27141 0.0100394 -0.000398728 -0.000848339 +EDGE3 1087 1138 -0.888182 12.5287 -6.41397 -0.00101225 0.00164728 0.125147 +EDGE3 1088 1137 -0.867487 -12.5327 -6.14717 -0.00163485 -0.0062262 -0.127204 +EDGE3 1089 1139 -0.0987892 0.00556001 -6.27803 -0.00392567 -0.00782832 -0.0043616 +EDGE3 1088 1139 -0.875542 12.5133 -6.42399 0.00989572 0.00718132 0.127078 +EDGE3 1089 1138 -0.89189 -12.5038 -6.15741 0.0067184 0.000656689 -0.122156 +EDGE3 1090 1140 -0.113966 0.00208943 -6.27087 0.000670377 -0.000912757 0.00787094 +EDGE3 1089 1140 -0.887397 12.517 -6.40755 0.00414071 0.00289189 0.127287 +EDGE3 1090 1139 -0.881523 -12.5174 -6.17016 -0.000351448 0.014347 -0.124184 +EDGE3 1091 1141 -0.124202 0.00295499 -6.27776 -0.000503642 -0.000975296 1.37225e-05 +EDGE3 1090 1141 -0.915778 12.5166 -6.41626 -0.00438083 -0.00370541 0.132603 +EDGE3 1091 1140 -0.893598 -12.5089 -6.16473 0.00592008 -0.00352478 -0.12203 +EDGE3 1092 1142 -0.129381 0.00544804 -6.29541 0.00302814 -0.00229747 0.00657968 +EDGE3 1091 1142 -0.919333 12.5131 -6.39722 -0.0136385 0.000758554 0.119932 +EDGE3 1092 1141 -0.912312 -12.497 -6.1554 -0.00714949 0.00374814 -0.125657 +EDGE3 1093 1143 -0.141795 0.00806683 -6.27518 0.0047886 -0.0058043 -0.00343647 +EDGE3 1092 1143 -0.914027 12.5149 -6.41402 0.00698689 -0.0028781 0.132316 +EDGE3 1093 1142 -0.919735 -12.525 -6.15504 0.00510256 -0.000182855 -0.125697 +EDGE3 1094 1144 -0.166421 0.00606214 -6.28296 0.000374797 0.00587916 0.0042037 +EDGE3 1093 1144 -0.936606 12.515 -6.41444 0.00162268 0.000931264 0.128989 +EDGE3 1094 1143 -0.91299 -12.5135 -6.15346 -0.00573733 0.00848649 -0.129095 +EDGE3 1095 1145 -0.154578 0.00122621 -6.27942 0.00607516 0.000997757 -0.00238887 +EDGE3 1094 1145 -0.944486 12.503 -6.3932 0.000661065 -0.00186277 0.136708 +EDGE3 1095 1144 -0.937622 -12.5044 -6.15589 -0.00136383 -0.00957742 -0.130975 +EDGE3 1096 1146 -0.165094 0.00209877 -6.294 -0.00433526 0.00127575 -0.00394661 +EDGE3 1095 1146 -0.939003 12.505 -6.39882 0.0044036 0.00202793 0.123312 +EDGE3 1097 1147 -0.174899 -0.00612051 -6.27081 0.00204433 0.007099 0.00186977 +EDGE3 1096 1145 -0.955157 -12.5163 -6.17346 0.00409817 0.006041 -0.127833 +EDGE3 1096 1147 -0.961609 12.5179 -6.39155 0.00204675 -0.00390506 0.133012 +EDGE3 1097 1146 -0.94185 -12.5076 -6.12955 -0.00377234 -0.000429559 -0.128042 +EDGE3 1098 1148 -0.183013 0.0101433 -6.28188 -0.00189697 -0.00206328 -0.00286082 +EDGE3 1097 1148 -0.965557 12.5181 -6.41087 0.00258561 0.000486965 0.13112 +EDGE3 1099 1149 -0.182364 0.0068286 -6.27621 0.000141089 0.000234572 -0.000813911 +EDGE3 1098 1147 -0.949378 -12.5049 -6.15245 -0.00756487 0.0020052 -0.124889 +EDGE3 1098 1149 -0.968069 12.5191 -6.39378 -0.000471492 -0.00097045 0.125785 +EDGE3 1099 1148 -0.970387 -12.5038 -6.18284 0.00485415 -0.00384521 -0.121302 +EDGE3 1100 1150 -0.197281 0.0098871 -6.28516 -0.00484884 0.00676031 0.00621865 +EDGE3 1099 1150 -0.97585 12.5337 -6.40475 3.53013e-05 -0.00710516 0.124239 +EDGE3 1100 1149 -0.966361 -12.5097 -6.15233 -0.000943084 0.00651667 -0.118789 +EDGE3 1101 1151 -0.192477 -0.00135961 -6.28448 0.00107028 0.00826492 0.000232148 +EDGE3 1100 1151 -0.993534 12.4989 -6.41365 -0.00214601 0.00424887 0.127495 +EDGE3 1102 1152 -0.20576 0.00479457 -6.28118 -0.00240482 -0.00546877 -0.000109253 +EDGE3 1101 1150 -0.97874 -12.5071 -6.15667 0.00297478 0.00446162 -0.121113 +EDGE3 1101 1152 -1.00439 12.5047 -6.40834 -0.00642854 0.00221269 0.119191 +EDGE3 1102 1151 -1.02303 -12.4903 -6.16081 0.00936253 0.0053886 -0.117043 +EDGE3 1103 1153 -0.227326 0.0151366 -6.2743 0.000669211 -0.00327835 -0.00113438 +EDGE3 1102 1153 -0.991906 12.4954 -6.41187 0.000557244 -0.00457961 0.128665 +EDGE3 1103 1152 -1.00386 -12.4961 -6.1534 0.00530795 0.00183167 -0.128995 +EDGE3 1104 1154 -0.20562 -0.0103333 -6.28251 -0.000770337 0.00495012 0.00490129 +EDGE3 1103 1154 -1.01864 12.5289 -6.4025 -0.00954296 -0.00467357 0.124002 +EDGE3 1104 1153 -1.01472 -12.505 -6.14222 0.000943881 -0.00237764 -0.131712 +EDGE3 1105 1155 -0.233487 0.0156592 -6.2919 -0.00307039 0.00736793 0.000524926 +EDGE3 1104 1155 -1.01576 12.4977 -6.39919 -0.000217362 -0.000540274 0.125859 +EDGE3 1105 1154 -0.998059 -12.5003 -6.14902 -0.00190637 0.00431375 -0.131983 +EDGE3 1106 1156 -0.249008 0.0111789 -6.26149 -0.00795216 0.000400304 0.0054032 +EDGE3 1105 1156 -1.04198 12.5149 -6.40396 -0.00103399 -0.00173012 0.130534 +EDGE3 1106 1155 -1.03128 -12.5115 -6.1508 -0.00334882 -0.00254142 -0.123098 +EDGE3 1107 1157 -0.267114 -0.0108505 -6.2652 -0.00424052 0.00224323 0.00385502 +EDGE3 1106 1157 -1.04186 12.518 -6.39461 0.00530245 0.000875085 0.128863 +EDGE3 1107 1156 -1.03029 -12.4993 -6.14479 -0.00488674 -0.00379305 -0.120569 +EDGE3 1108 1158 -0.267896 -0.00180163 -6.274 0.00481841 0.000862869 0.00374872 +EDGE3 1107 1158 -1.04674 12.5028 -6.39934 0.0114884 -0.00119308 0.126397 +EDGE3 1108 1157 -1.03347 -12.4941 -6.14574 -0.00195252 -0.000725568 -0.126743 +EDGE3 1109 1159 -0.262922 0.00307386 -6.27473 0.000710437 -0.00397651 4.80272e-05 +EDGE3 1108 1159 -1.06708 12.4959 -6.39241 -0.00420049 0.000143168 0.12012 +EDGE3 1110 1160 -0.291329 0.001467 -6.29047 -0.0056683 -0.000296991 0.00187339 +EDGE3 1109 1158 -1.04916 -12.4837 -6.14632 -0.00189699 -0.00340629 -0.123477 +EDGE3 1109 1160 -1.07353 12.5091 -6.39514 -0.00179805 0.00625127 0.124588 +EDGE3 1110 1159 -1.05825 -12.4965 -6.1482 -0.00394227 0.00281992 -0.122474 +EDGE3 1111 1161 -0.290128 -0.000431997 -6.26954 0.00632831 -0.000248789 0.009529 +EDGE3 1110 1161 -1.07269 12.5087 -6.40273 -0.00984037 0.00413139 0.130199 +EDGE3 1111 1160 -1.07036 -12.4982 -6.16617 -0.00141526 -0.00304624 -0.114398 +EDGE3 1112 1162 -0.290437 0.0135134 -6.28197 -7.83919e-05 -0.000368196 -0.00634729 +EDGE3 1111 1162 -1.07818 12.4999 -6.41405 -0.00906332 -0.00118348 0.118044 +EDGE3 1112 1161 -1.07025 -12.4968 -6.16223 -0.000366692 -0.00125681 -0.130316 +EDGE3 1113 1163 -0.305132 0.0072518 -6.28435 -0.00378351 -0.00675076 -0.00867628 +EDGE3 1112 1163 -1.09356 12.4986 -6.41101 0.011558 -0.000753522 0.116756 +EDGE3 1114 1164 -0.292756 0.0083907 -6.27806 0.00142468 0.000935005 -0.00275041 +EDGE3 1113 1162 -1.06703 -12.4818 -6.12884 -0.00276761 -0.00258534 -0.128452 +EDGE3 1113 1164 -1.10781 12.4909 -6.39269 -0.00430571 -0.00982759 0.125231 +EDGE3 1114 1163 -1.07098 -12.4849 -6.16523 -8.84263e-06 -1.10456e-05 -0.13083 +EDGE3 1115 1165 -0.317373 0.000611869 -6.27525 -0.0102376 0.00122091 -0.00851337 +EDGE3 1114 1165 -1.10531 12.4968 -6.38615 0.00611183 -0.00311739 0.134007 +EDGE3 1116 1166 -0.315932 0.00761311 -6.27221 -0.00453342 5.68516e-05 -0.00233333 +EDGE3 1115 1164 -1.1022 -12.4953 -6.15233 -0.00179131 -0.000770119 -0.124698 +EDGE3 1115 1166 -1.13358 12.514 -6.40399 -0.00524425 0.00238572 0.129481 +EDGE3 1116 1165 -1.09707 -12.4932 -6.15464 -0.00187637 0.00141395 -0.13028 +EDGE3 1117 1167 -0.329076 0.00306938 -6.26731 -0.0035933 0.00437327 0.00163566 +EDGE3 1116 1167 -1.11187 12.4821 -6.40888 -0.00758156 0.000363913 0.11873 +EDGE3 1117 1166 -1.10518 -12.4987 -6.13346 -0.00527378 -0.00759503 -0.121498 +EDGE3 1118 1168 -0.334661 0.00281413 -6.2652 -0.00258763 0.006578 0.000108296 +EDGE3 1117 1168 -1.13046 12.4936 -6.40269 -0.00489374 -0.00309957 0.137602 +EDGE3 1118 1167 -1.12059 -12.4988 -6.14696 -0.0022611 0.00222554 -0.135732 +EDGE3 1119 1169 -0.370959 0.0134238 -6.27035 0.00805687 -0.00194641 -0.000756692 +EDGE3 1118 1169 -1.13911 12.4813 -6.40489 -0.00286812 0.00121766 0.114926 +EDGE3 1119 1168 -1.13137 -12.4763 -6.15619 -0.00235513 0.00589098 -0.122065 +EDGE3 1120 1170 -0.354939 0.0120693 -6.26792 -0.00504379 -0.00662669 0.00211435 +EDGE3 1119 1170 -1.12717 12.4919 -6.39848 -0.00532776 0.000484042 0.121484 +EDGE3 1120 1169 -1.1338 -12.4896 -6.15676 -0.00700229 -0.000769194 -0.127495 +EDGE3 1121 1171 -0.368385 -0.0117644 -6.24798 -0.00590976 -0.00514894 0.00455674 +EDGE3 1120 1171 -1.15302 12.4822 -6.40702 0.00215277 -0.00862968 0.126863 +EDGE3 1121 1170 -1.12311 -12.4826 -6.14444 0.0063806 -0.00438645 -0.127325 +EDGE3 1122 1172 -0.394286 -0.00407713 -6.27858 -0.00485079 0.000317228 0.00493517 +EDGE3 1121 1172 -1.18002 12.4972 -6.38416 -0.00302051 -0.000830927 0.131673 +EDGE3 1122 1171 -1.14042 -12.4763 -6.13725 -0.00172928 -0.00624078 -0.124985 +EDGE3 1123 1173 -0.366899 -0.00161897 -6.29175 -0.00508234 0.0109501 0.00786028 +EDGE3 1122 1173 -1.16627 12.4765 -6.39602 -0.00193793 0.00243046 0.126608 +EDGE3 1123 1172 -1.16721 -12.4911 -6.1294 0.00140047 0.00701018 -0.131134 +EDGE3 1124 1174 -0.383681 -0.01491 -6.25964 0.00419434 -0.00423263 -0.0100899 +EDGE3 1123 1174 -1.17847 12.4846 -6.4099 0.0029396 0.00295888 0.13103 +EDGE3 1124 1173 -1.16932 -12.4734 -6.15568 0.00555355 0.00287042 -0.128975 +EDGE3 1125 1175 -0.400121 0.0076747 -6.27039 -0.00588675 0.00102817 0.00122083 +EDGE3 1124 1175 -1.16705 12.4776 -6.38223 0.00174903 0.00844701 0.128263 +EDGE3 1125 1174 -1.15388 -12.4636 -6.1313 0.00236248 0.00639083 -0.12525 +EDGE3 1126 1176 -0.393196 0.000278181 -6.26279 0.0111172 0.00650104 0.00118288 +EDGE3 1125 1176 -1.20199 12.4682 -6.39378 -0.0001634 -0.00334664 0.131098 +EDGE3 1126 1175 -1.17806 -12.4935 -6.14965 -0.00672026 -0.00763399 -0.123712 +EDGE3 1127 1177 -0.408955 -0.0106567 -6.28594 -0.00143213 0.00440894 -0.00121945 +EDGE3 1126 1177 -1.20365 12.4795 -6.39071 -0.00227853 0.000721709 0.123161 +EDGE3 1127 1176 -1.18872 -12.4777 -6.1465 -0.0055142 0.00356504 -0.135225 +EDGE3 1128 1178 -0.404673 0.00502308 -6.26392 0.00857917 0.00294463 -0.00614155 +EDGE3 1127 1178 -1.21329 12.4818 -6.38577 0.0010936 0.00480299 0.125881 +EDGE3 1128 1177 -1.17338 -12.4754 -6.15075 0.00366834 0.00538329 -0.127241 +EDGE3 1129 1179 -0.434678 0.00753375 -6.2782 0.00371986 -0.0037118 -0.000104051 +EDGE3 1128 1179 -1.20476 12.4635 -6.38293 -0.00166745 0.0004277 0.129091 +EDGE3 1129 1178 -1.18936 -12.4667 -6.13828 -0.00173314 0.00140469 -0.126736 +EDGE3 1130 1180 -0.446793 -0.00125806 -6.25365 0.00727707 0.00129413 0.00574578 +EDGE3 1129 1180 -1.23446 12.4679 -6.40268 -0.00230645 -0.00735853 0.124157 +EDGE3 1130 1179 -1.21512 -12.4798 -6.12957 -0.00112857 -0.0048296 -0.122774 +EDGE3 1131 1181 -0.43429 -0.00163414 -6.25789 -0.00698041 -0.011099 -0.00453026 +EDGE3 1130 1181 -1.24254 12.464 -6.38143 0.00771033 0.0032751 0.124741 +EDGE3 1131 1180 -1.21108 -12.4698 -6.14472 -9.11429e-05 -0.00941339 -0.126362 +EDGE3 1132 1182 -0.451668 -0.00670992 -6.264 -0.00265706 0.000763521 0.00442736 +EDGE3 1131 1182 -1.23863 12.4713 -6.4022 -0.00241968 -0.00585911 0.126309 +EDGE3 1132 1181 -1.22861 -12.4557 -6.12607 0.00604151 0.00134307 -0.123231 +EDGE3 1133 1183 -0.46563 -0.00588496 -6.27225 -0.00761845 -0.00399791 -0.000888786 +EDGE3 1132 1183 -1.23214 12.4801 -6.37229 0.0011017 0.00141825 0.123807 +EDGE3 1133 1182 -1.22353 -12.4654 -6.12973 0.00569313 -0.00361411 -0.121587 +EDGE3 1134 1184 -0.474359 -0.0113289 -6.26268 0.00379009 0.00436689 0.00194472 +EDGE3 1133 1184 -1.2414 12.4671 -6.39577 -0.000649172 0.00294076 0.127997 +EDGE3 1134 1183 -1.23828 -12.4574 -6.14626 0.00510683 -0.000745595 -0.132677 +EDGE3 1135 1185 -0.474928 -0.00563032 -6.2688 -0.00218833 -0.00994081 0.0110615 +EDGE3 1134 1185 -1.2545 12.467 -6.38094 0.000409748 0.00553728 0.127049 +EDGE3 1135 1184 -1.23746 -12.4592 -6.13676 -0.0092394 0.000263692 -0.126086 +EDGE3 1136 1186 -0.482346 -0.00418313 -6.26197 0.00323975 -0.00671356 -0.0116578 +EDGE3 1135 1186 -1.27084 12.453 -6.394 -0.00182894 0.00443698 0.126412 +EDGE3 1136 1185 -1.25762 -12.4344 -6.14642 -0.0155331 0.000385683 -0.134145 +EDGE3 1137 1187 -0.49667 2.46165e-05 -6.25282 -0.00412981 -0.0098808 0.000812814 +EDGE3 1136 1187 -1.27627 12.4508 -6.38308 0.0112331 -0.0034759 0.119962 +EDGE3 1137 1186 -1.27274 -12.4508 -6.15342 -0.0102071 0.000189771 -0.123034 +EDGE3 1138 1188 -0.510962 -0.00449185 -6.29165 0.00883581 -4.61351e-05 0.00687042 +EDGE3 1137 1188 -1.27963 12.4535 -6.4008 -0.00281529 -0.00265015 0.120812 +EDGE3 1138 1187 -1.26168 -12.4533 -6.10848 0.00470036 -0.00557284 -0.122271 +EDGE3 1139 1189 -0.502879 -0.00259996 -6.251 -0.00639205 -0.00160921 -0.00314994 +EDGE3 1138 1189 -1.3073 12.4334 -6.40493 -0.00125572 0.00320951 0.122231 +EDGE3 1139 1188 -1.26125 -12.4527 -6.1372 -0.00349041 0.000443425 -0.123466 +EDGE3 1140 1190 -0.505676 -0.00320927 -6.2545 0.00355525 0.00459492 -0.00177641 +EDGE3 1139 1190 -1.29707 12.4539 -6.39549 -0.000248724 0.00508721 0.132889 +EDGE3 1140 1189 -1.29575 -12.4314 -6.14881 0.00381312 0.00284565 -0.123623 +EDGE3 1141 1191 -0.551153 -0.0201324 -6.25561 -0.00417653 0.0039219 -0.00366754 +EDGE3 1140 1191 -1.32546 12.4504 -6.37074 -0.00518676 -0.00208013 0.126404 +EDGE3 1141 1190 -1.29858 -12.45 -6.13345 -0.000487034 -0.00458502 -0.126707 +EDGE3 1142 1192 -0.538303 -0.00465327 -6.26118 0.00870901 0.00776655 -0.00114944 +EDGE3 1141 1192 -1.33001 12.4323 -6.38018 0.00930426 0.00559845 0.130761 +EDGE3 1142 1191 -1.28876 -12.4357 -6.12471 -0.00976616 0.00254014 -0.135864 +EDGE3 1143 1193 -0.536172 -0.00665845 -6.24827 -0.00100424 -0.000314238 0.00418091 +EDGE3 1142 1193 -1.32558 12.4376 -6.38176 0.00110592 -0.00381456 0.117852 +EDGE3 1143 1192 -1.32285 -12.4549 -6.13039 -0.00447119 -0.00769086 -0.124213 +EDGE3 1144 1194 -0.557223 -0.00414318 -6.24913 0.00020639 -0.00883285 0.0052873 +EDGE3 1143 1194 -1.32877 12.4599 -6.38804 -6.73799e-05 0.00829707 0.116383 +EDGE3 1144 1193 -1.3185 -12.4478 -6.13446 0.00111132 0.00401293 -0.121848 +EDGE3 1145 1195 -0.560861 0.00253176 -6.25091 0.00247524 0.000115599 -0.00455864 +EDGE3 1144 1195 -1.32834 12.4463 -6.38486 -0.000986783 0.000957479 0.119914 +EDGE3 1145 1194 -1.29091 -12.4488 -6.11485 0.00232274 -0.00933427 -0.118718 +EDGE3 1146 1196 -0.551998 0.00155121 -6.26379 0.00505227 0.00473573 -0.00217483 +EDGE3 1145 1196 -1.35228 12.4529 -6.39977 -0.00222373 0.00316324 0.128741 +EDGE3 1146 1195 -1.32114 -12.4574 -6.13544 0.00633365 -0.00753104 -0.12892 +EDGE3 1147 1197 -0.562501 0.00942395 -6.26038 0.0033491 0.000513356 -0.00189708 +EDGE3 1146 1197 -1.35097 12.43 -6.38535 -0.00737338 0.00443769 0.1223 +EDGE3 1147 1196 -1.33939 -12.4371 -6.14619 -0.00830984 0.00217976 -0.123683 +EDGE3 1148 1198 -0.590994 0.0192849 -6.2698 -0.00202452 -0.00368814 -0.00685307 +EDGE3 1147 1198 -1.3738 12.4478 -6.38487 0.00222474 -0.00058079 0.119631 +EDGE3 1148 1197 -1.33111 -12.4588 -6.12577 -0.00253556 -0.000320812 -0.130778 +EDGE3 1149 1199 -0.587603 -0.000896544 -6.2723 0.00326635 0.000227711 -0.000139426 +EDGE3 1148 1199 -1.37133 12.4424 -6.38131 -0.000849926 0.00610281 0.125046 +EDGE3 1149 1198 -1.3548 -12.4257 -6.1194 0.00751652 0.00605468 -0.118622 +EDGE3 1150 1200 -0.59432 -0.00309264 -6.26435 0.00662331 0.00768897 -0.00616144 +EDGE3 1149 1200 -1.37716 12.4124 -6.38937 0.00182846 0.00877233 0.132345 +EDGE3 1150 1199 -1.35851 -12.4496 -6.13635 0.00781719 -0.000305581 -0.130435 +EDGE3 1151 1201 -0.586411 -0.00197727 -6.25899 -1.80105e-05 0.00136251 0.0045931 +EDGE3 1150 1201 -1.39733 12.4237 -6.38844 0.0025011 0.00630897 0.11704 +EDGE3 1151 1200 -1.37493 -12.4266 -6.12415 0.00570452 0.00149984 -0.12929 +EDGE3 1152 1202 -0.595211 -0.000157541 -6.26593 0.00210539 0.00568672 0.00270636 +EDGE3 1151 1202 -1.39162 12.4349 -6.38536 0.000541972 0.00410612 0.120554 +EDGE3 1152 1201 -1.37092 -12.4439 -6.12784 0.00295538 0.00150208 -0.126699 +EDGE3 1153 1203 -0.635168 -0.00486661 -6.24583 0.00282225 -0.00286902 0.00439298 +EDGE3 1152 1203 -1.41501 12.4461 -6.37822 -0.000295701 0.00348059 0.129702 +EDGE3 1153 1202 -1.37921 -12.418 -6.14436 -0.00451733 0.00483192 -0.124277 +EDGE3 1154 1204 -0.600757 0.00226591 -6.24939 -0.00655518 0.00339705 0.00772898 +EDGE3 1153 1204 -1.42801 12.4329 -6.37841 0.00189543 -0.00580807 0.128183 +EDGE3 1154 1203 -1.39093 -12.4048 -6.12743 -0.0044348 0.000535885 -0.122091 +EDGE3 1155 1205 -0.627949 -0.00160153 -6.26067 -0.00543475 -0.00255809 0.000653994 +EDGE3 1154 1205 -1.41601 12.4263 -6.39838 0.00313799 0.00116731 0.128462 +EDGE3 1155 1204 -1.41182 -12.4276 -6.1253 0.000853007 -0.00487916 -0.127081 +EDGE3 1156 1206 -0.636788 -0.00066393 -6.24982 0.0024096 0.00113378 0.00552543 +EDGE3 1155 1206 -1.43575 12.4268 -6.37132 -0.0014241 0.00499067 0.127249 +EDGE3 1156 1205 -1.40524 -12.4303 -6.13553 -0.00177166 0.00326531 -0.127681 +EDGE3 1157 1207 -0.6448 -0.0165122 -6.25331 0.00430846 -0.000585867 -0.00118496 +EDGE3 1156 1207 -1.45617 12.421 -6.4 0.0117396 -0.00686455 0.131121 +EDGE3 1157 1206 -1.4231 -12.4117 -6.1256 -0.000129109 0.00215538 -0.130824 +EDGE3 1158 1208 -0.663585 -0.00767057 -6.25304 0.00560569 0.000647777 0.00285543 +EDGE3 1157 1208 -1.43514 12.4089 -6.3803 0.00325477 -0.00553079 0.125687 +EDGE3 1158 1207 -1.41294 -12.4241 -6.11132 0.00610925 -0.00106644 -0.125066 +EDGE3 1159 1209 -0.67398 -0.0106482 -6.23675 -0.00153959 -0.00836891 -0.0116235 +EDGE3 1158 1209 -1.44371 12.4257 -6.36928 -0.0062069 0.00536281 0.117764 +EDGE3 1159 1208 -1.43823 -12.4233 -6.10205 -0.000103496 -0.00190288 -0.124737 +EDGE3 1160 1210 -0.679385 0.013206 -6.25238 -0.000164712 0.000626074 -0.00497088 +EDGE3 1160 1209 -1.44299 -12.4073 -6.1134 -0.00465573 0.00956272 -0.127114 +EDGE3 1159 1210 -1.44685 12.4045 -6.38246 0.00955379 0.00315166 0.122554 +EDGE3 1161 1211 -0.679047 -0.0135624 -6.25026 -0.00289291 -0.00138044 -0.00169663 +EDGE3 1160 1211 -1.45841 12.4152 -6.36943 0.00100184 -0.00666248 0.126239 +EDGE3 1161 1210 -1.45473 -12.4167 -6.13224 0.00589661 0.000328984 -0.127899 +EDGE3 1162 1212 -0.686377 -0.00321335 -6.25032 -0.00135121 -0.0032389 -0.00222297 +EDGE3 1161 1212 -1.47143 12.4137 -6.35941 0.00395357 -0.000711455 0.130383 +EDGE3 1162 1211 -1.44657 -12.4068 -6.11333 0.0049946 0.00233977 -0.118389 +EDGE3 1163 1213 -0.701179 -0.00604158 -6.25104 0.00856247 0.000594793 0.0035117 +EDGE3 1162 1213 -1.4842 12.4078 -6.37056 -0.00703041 -0.00157224 0.132491 +EDGE3 1163 1212 -1.46823 -12.4002 -6.12652 0.00633445 0.000530256 -0.118726 +EDGE3 1164 1214 -0.70435 -0.0047501 -6.2457 0.0048552 0.000659478 0.00619372 +EDGE3 1163 1214 -1.50486 12.4034 -6.37587 -0.0173164 0.00211157 0.137258 +EDGE3 1164 1213 -1.47391 -12.4096 -6.12384 -0.000689562 -0.00470653 -0.118704 +EDGE3 1165 1215 -0.70691 -0.00886458 -6.22262 -0.00044565 0.000692605 -0.00885956 +EDGE3 1165 1214 -1.46885 -12.4131 -6.12485 -0.00380164 -0.0130799 -0.125222 +EDGE3 1164 1215 -1.50313 12.4 -6.39051 0.000789801 -0.0018477 0.126353 +EDGE3 1166 1216 -0.705393 0.0045749 -6.23281 -0.00086591 -0.000245656 -0.00196658 +EDGE3 1165 1216 -1.51739 12.3849 -6.36889 0.00041872 -0.00251242 0.135977 +EDGE3 1166 1215 -1.48058 -12.3936 -6.11618 -0.00219755 0.00496567 -0.125051 +EDGE3 1167 1217 -0.718231 -0.0228425 -6.22801 0.0106428 -0.00186047 0.00153311 +EDGE3 1166 1217 -1.51621 12.3991 -6.36484 0.00162031 0.00261421 0.123418 +EDGE3 1168 1218 -0.73265 0.00157157 -6.26599 -0.00473128 -0.00678256 0.00318402 +EDGE3 1167 1216 -1.48909 -12.409 -6.11174 0.00740139 0.00395354 -0.113494 +EDGE3 1167 1218 -1.53665 12.3936 -6.36287 0.0091274 -0.00551667 0.128787 +EDGE3 1168 1217 -1.50762 -12.4263 -6.10888 0.0108017 -0.00142379 -0.125029 +EDGE3 1169 1219 -0.735563 0.00484933 -6.23511 0.00427211 -0.00627739 -0.00159464 +EDGE3 1168 1219 -1.53195 12.3919 -6.36695 -0.00516485 0.00177597 0.125843 +EDGE3 1169 1218 -1.50259 -12.3838 -6.11001 0.00571677 0.00222725 -0.117759 +EDGE3 1170 1220 -0.7572 0.0303086 -6.25535 0.00505249 -0.00414314 -0.00583963 +EDGE3 1169 1220 -1.53628 12.3864 -6.35881 -0.00390475 0.00101454 0.126971 +EDGE3 1170 1219 -1.50543 -12.3905 -6.109 -0.00324758 -0.00668458 -0.133453 +EDGE3 1171 1221 -0.753061 0.00369138 -6.23582 -0.000606474 -0.00228344 -0.00372008 +EDGE3 1170 1221 -1.53767 12.3826 -6.35654 0.00349867 -0.00114773 0.129268 +EDGE3 1171 1220 -1.5164 -12.3859 -6.11212 0.00336792 -0.0123343 -0.130266 +EDGE3 1172 1222 -0.763491 0.0106626 -6.23321 -0.000962191 -0.00369468 0.00694799 +EDGE3 1171 1222 -1.57513 12.3776 -6.37447 -0.00033356 -0.00826851 0.123252 +EDGE3 1172 1221 -1.52038 -12.3764 -6.10855 -0.00396646 -0.00158179 -0.119533 +EDGE3 1173 1223 -0.763488 -0.0107969 -6.24917 -0.00985355 -0.00141101 0.00847526 +EDGE3 1172 1223 -1.56717 12.3823 -6.35321 0.00511763 0.00327859 0.11817 +EDGE3 1173 1222 -1.53533 -12.3802 -6.1047 -0.00371159 -0.00354694 -0.127693 +EDGE3 1174 1224 -0.777216 -0.0098318 -6.23862 -0.0017637 -0.0043056 0.000635683 +EDGE3 1173 1224 -1.56544 12.3868 -6.34448 -0.00549841 -0.0021243 0.120657 +EDGE3 1174 1223 -1.52344 -12.3975 -6.12241 0.00210697 -0.0061466 -0.12554 +EDGE3 1175 1225 -0.781507 -0.0112002 -6.24903 0.00659307 -0.00539597 -0.00512159 +EDGE3 1174 1225 -1.58304 12.385 -6.37081 0.000650196 -0.00327674 0.133791 +EDGE3 1175 1224 -1.54609 -12.3768 -6.10079 0.00831849 -0.00136114 -0.121132 +EDGE3 1176 1226 -0.804981 0.00202589 -6.24009 -0.00346532 -0.00218222 -0.00376092 +EDGE3 1175 1226 -1.57726 12.3745 -6.35364 0.00628964 -0.0058507 0.127389 +EDGE3 1176 1225 -1.5553 -12.3718 -6.1218 -0.00660064 0.00253584 -0.129355 +EDGE3 1177 1227 -0.793313 -0.00266463 -6.23934 -0.00376673 0.00756279 -0.00919838 +EDGE3 1176 1227 -1.58679 12.3671 -6.36993 -0.00293694 0.00735976 0.122177 +EDGE3 1177 1226 -1.55463 -12.3735 -6.09386 0.00425956 0.00556456 -0.129283 +EDGE3 1178 1228 -0.81202 0.00839967 -6.23836 -0.00342949 -0.00510324 0.000481975 +EDGE3 1177 1228 -1.58444 12.3793 -6.34453 -0.0130475 0.00234623 0.131364 +EDGE3 1178 1227 -1.56988 -12.3775 -6.09538 0.00170343 -0.00855224 -0.118549 +EDGE3 1179 1229 -0.819681 -0.00146664 -6.21548 0.0024772 0.00142246 -0.0010728 +EDGE3 1178 1229 -1.60239 12.3775 -6.33719 -0.00364842 0.000428227 0.116919 +EDGE3 1179 1228 -1.57759 -12.3528 -6.10399 0.000922843 -0.0023273 -0.125846 +EDGE3 1180 1230 -0.826948 0.00702994 -6.23185 -0.000792159 0.00573375 0.00366799 +EDGE3 1179 1230 -1.60736 12.3585 -6.36222 -0.00883054 -0.00284198 0.130768 +EDGE3 1180 1229 -1.58947 -12.3665 -6.11719 -0.00318914 -0.014479 -0.131971 +EDGE3 1181 1231 -0.819097 -0.0144827 -6.22762 0.0164132 -0.00254258 -0.00242639 +EDGE3 1180 1231 -1.64084 12.3531 -6.36304 -0.00125319 -0.00220802 0.124162 +EDGE3 1181 1230 -1.59255 -12.3911 -6.10882 -0.00121015 -0.000936434 -0.134288 +EDGE3 1182 1232 -0.849732 -0.0104626 -6.21429 0.00518874 0.00475526 -0.0070891 +EDGE3 1181 1232 -1.64576 12.3513 -6.35973 -0.00397475 -0.00255912 0.139053 +EDGE3 1183 1233 -0.848792 0.00276789 -6.24248 0.00663918 0.000641935 0.00324398 +EDGE3 1182 1231 -1.60136 -12.3521 -6.1019 -0.00189278 0.0154098 -0.12539 +EDGE3 1182 1233 -1.63958 12.3544 -6.35841 0.00241164 -0.00278116 0.132014 +EDGE3 1183 1232 -1.59689 -12.3727 -6.11118 -0.00526534 -0.000953964 -0.123822 +EDGE3 1184 1234 -0.858642 -0.00535503 -6.22055 -0.00154394 -0.0026196 0.00413952 +EDGE3 1183 1234 -1.65459 12.3641 -6.35624 0.000139436 -0.00187189 0.122093 +EDGE3 1185 1235 -0.867928 0.0151242 -6.2251 0.0040971 -0.00499601 -0.00218141 +EDGE3 1184 1233 -1.62664 -12.3624 -6.11224 0.000566359 -0.00664919 -0.122561 +EDGE3 1184 1235 -1.65701 12.3592 -6.34187 -0.0145183 0.00303589 0.12618 +EDGE3 1185 1234 -1.62961 -12.359 -6.10785 -0.000682001 -0.0154569 -0.117635 +EDGE3 1186 1236 -0.880972 0.00449595 -6.2451 0.00284941 0.00389047 -0.000919068 +EDGE3 1185 1236 -1.67055 12.3545 -6.33324 -0.0042438 0.00563803 0.138882 +EDGE3 1186 1235 -1.62868 -12.3518 -6.10943 -0.0104544 0.0021298 -0.130561 +EDGE3 1187 1237 -0.897219 0.00473512 -6.21713 0.00305191 0.00129906 -0.000465018 +EDGE3 1186 1237 -1.67452 12.3573 -6.34577 0.00361794 -0.000286836 0.129597 +EDGE3 1187 1236 -1.64955 -12.3376 -6.09292 -0.00624895 0.0102394 -0.12062 +EDGE3 1188 1238 -0.894591 0.0157677 -6.22303 0.000837784 0.00226877 -0.00314804 +EDGE3 1187 1238 -1.68594 12.3533 -6.34927 0.00391305 0.00859562 0.119104 +EDGE3 1188 1237 -1.61997 -12.3579 -6.08902 0.00981328 0.00253788 -0.114168 +EDGE3 1189 1239 -0.910828 -0.00292587 -6.2126 -0.00368063 -0.00993909 0.00374927 +EDGE3 1188 1239 -1.69598 12.3509 -6.3315 -0.00334413 0.0104578 0.130202 +EDGE3 1189 1238 -1.64359 -12.3495 -6.1157 0.00518003 -0.00876998 -0.128567 +EDGE3 1190 1240 -0.894763 -0.00565593 -6.215 0.00231346 0.00537624 0.00327782 +EDGE3 1189 1240 -1.69179 12.3428 -6.33005 0.00673863 0.00593239 0.128766 +EDGE3 1190 1239 -1.66718 -12.3422 -6.09574 -0.00459611 -0.00989935 -0.130184 +EDGE3 1191 1241 -0.913107 -0.00505721 -6.20033 -0.00218368 -0.00149836 0.00205478 +EDGE3 1190 1241 -1.69225 12.3359 -6.34792 0.0011659 0.00249614 0.136879 +EDGE3 1191 1240 -1.6619 -12.3393 -6.09342 0.00197051 -0.0100604 -0.120317 +EDGE3 1192 1242 -0.917034 0.00391925 -6.21638 0.00537179 -0.00126021 -0.00268889 +EDGE3 1191 1242 -1.70746 12.3452 -6.33797 -0.00416107 0.00363011 0.12321 +EDGE3 1192 1241 -1.65792 -12.3381 -6.10052 0.0064255 -0.00338841 -0.129358 +EDGE3 1193 1243 -0.92281 -0.0209285 -6.2046 0.00541615 -0.000899427 0.00097326 +EDGE3 1192 1243 -1.7232 12.3214 -6.33879 0.000147049 0.000997954 0.125844 +EDGE3 1193 1242 -1.67952 -12.3498 -6.09598 0.00570572 0.00126854 -0.122115 +EDGE3 1194 1244 -0.932399 0.0136746 -6.20022 0.000373589 0.000758173 -0.00511807 +EDGE3 1193 1244 -1.71445 12.3427 -6.33502 -0.00246144 0.00148607 0.120707 +EDGE3 1194 1243 -1.67639 -12.3325 -6.10116 0.000575354 -0.0006999 -0.128711 +EDGE3 1195 1245 -0.947068 -0.0159339 -6.21965 -0.0020889 0.00343984 -0.000447912 +EDGE3 1194 1245 -1.74262 12.3433 -6.32067 -0.00279331 -0.00139498 0.121312 +EDGE3 1195 1244 -1.6975 -12.3218 -6.10274 -0.00139401 -0.00598316 -0.121729 +EDGE3 1196 1246 -0.956521 0.00284064 -6.1981 0.00465378 -0.00846642 0.00434723 +EDGE3 1195 1246 -1.74668 12.3239 -6.33238 0.0045658 0.00689945 0.114054 +EDGE3 1196 1245 -1.71997 -12.3114 -6.09187 0.00447424 0.00354544 -0.123122 +EDGE3 1197 1247 -0.964136 0.0249829 -6.21537 0.00575565 0.00700707 -0.00216186 +EDGE3 1196 1247 -1.75594 12.3181 -6.35857 -0.0105942 0.00717302 0.131755 +EDGE3 1197 1246 -1.7055 -12.3234 -6.08857 0.00557127 0.00564596 -0.121938 +EDGE3 1198 1248 -0.942183 0.0212091 -6.21479 -0.00304121 -0.00543524 0.00371356 +EDGE3 1197 1248 -1.74687 12.3083 -6.3571 0.00406631 0.00278414 0.122172 +EDGE3 1198 1247 -1.72927 -12.3218 -6.07901 0.00083757 0.00306922 -0.122826 +EDGE3 1199 1249 -0.969275 0.00929195 -6.20055 0.0066406 -0.010653 -0.00292078 +EDGE3 1198 1249 -1.75837 12.3007 -6.33481 0.00463599 0.0100471 0.114156 +EDGE3 1199 1248 -1.74687 -12.2941 -6.0752 0.00121964 0.005099 -0.123172 +EDGE3 1199 1250 -1.76289 12.3132 -6.34708 -0.000409603 -0.00500224 0.122606 +EDGE3 1200 1250 -0.972567 -0.0135679 -6.1963 0.0036266 0.0118962 0.00300274 +EDGE3 1201 1251 -1.00084 -0.023625 -6.20128 0.0157634 0.00505926 0.00292634 +EDGE3 1200 1249 -1.72918 -12.3026 -6.06105 -0.000784109 0.0053741 -0.126668 +EDGE3 1200 1251 -1.75265 12.3054 -6.32302 -0.00156812 0.00282481 0.127818 +EDGE3 1201 1250 -1.72467 -12.3309 -6.0746 0.00335735 -0.0024894 -0.127736 +EDGE3 1202 1252 -0.996101 0.0119611 -6.19813 -0.00158611 -0.00687317 -0.00271154 +EDGE3 1201 1252 -1.80797 12.3031 -6.34114 -0.00305013 0.000366288 0.132034 +EDGE3 1202 1251 -1.74947 -12.316 -6.09044 0.00409927 -0.00368663 -0.130431 +EDGE3 1203 1253 -1.00038 -0.012893 -6.22226 -0.00231213 0.00156721 -0.00681858 +EDGE3 1202 1253 -1.79371 12.3035 -6.34167 0.00254504 -0.00508333 0.124495 +EDGE3 1203 1252 -1.76087 -12.2991 -6.07558 0.00214568 -0.00621734 -0.136847 +EDGE3 1204 1254 -1.0246 -0.0106408 -6.20367 0.00400399 -0.0086143 -0.0097092 +EDGE3 1203 1254 -1.8121 12.2913 -6.32236 0.000591115 0.00213519 0.123904 +EDGE3 1204 1253 -1.78266 -12.3085 -6.07163 -0.00334506 0.00512779 -0.130678 +EDGE3 1205 1255 -1.01535 -0.00579947 -6.1829 -0.0072431 -0.00118367 -0.000967873 +EDGE3 1204 1255 -1.81181 12.3012 -6.33358 0.00150901 -0.0052744 0.120237 +EDGE3 1205 1254 -1.75333 -12.2951 -6.08254 0.000711817 0.00215391 -0.127414 +EDGE3 1206 1256 -1.04132 -0.00887721 -6.20046 -0.00812428 -0.00332842 -0.00209666 +EDGE3 1205 1256 -1.80654 12.2732 -6.33852 -0.00752239 -0.00646584 0.124853 +EDGE3 1206 1255 -1.7928 -12.2968 -6.07913 -0.00365201 -0.00233409 -0.119524 +EDGE3 1207 1257 -1.03619 0.0111894 -6.21236 0.00504466 -0.00377497 0.00291732 +EDGE3 1206 1257 -1.82652 12.2776 -6.33292 -0.00839611 0.00308718 0.132292 +EDGE3 1207 1256 -1.79659 -12.2967 -6.06751 -0.00490736 0.00666142 -0.119734 +EDGE3 1208 1258 -1.06385 -0.0123796 -6.19049 0.00428118 -0.00262243 -0.00458791 +EDGE3 1207 1258 -1.84071 12.3061 -6.31205 0.00687508 -0.00476635 0.123949 +EDGE3 1208 1257 -1.79091 -12.2858 -6.07519 0.00597829 -0.00752509 -0.127747 +EDGE3 1209 1259 -1.05641 -0.00459719 -6.20575 -0.0017895 -0.0084225 -0.00455486 +EDGE3 1208 1259 -1.84033 12.2852 -6.2891 0.00793653 0.00740437 0.120969 +EDGE3 1209 1258 -1.79148 -12.2879 -6.06025 -0.00155408 -0.00524682 -0.119909 +EDGE3 1210 1260 -1.05354 -0.00756719 -6.18498 0.000613067 0.00713599 0.00804207 +EDGE3 1209 1260 -1.85116 12.2808 -6.32282 0.00482571 -0.0010936 0.132816 +EDGE3 1210 1259 -1.81046 -12.2856 -6.06614 0.000196469 -0.00418579 -0.115611 +EDGE3 1211 1261 -1.07177 -0.00722255 -6.17624 0.010805 0.00361448 -0.00580038 +EDGE3 1210 1261 -1.83089 12.2695 -6.32085 -0.00411543 0.00422507 0.132881 +EDGE3 1211 1260 -1.81693 -12.278 -6.06467 0.00143987 0.00332467 -0.137683 +EDGE3 1212 1262 -1.07532 0.00167455 -6.18548 0.0123053 0.0011156 -0.00439697 +EDGE3 1211 1262 -1.86153 12.2805 -6.31079 0.00366122 0.0116569 0.124319 +EDGE3 1212 1261 -1.82467 -12.292 -6.07596 0.000532281 -0.0108006 -0.127354 +EDGE3 1213 1263 -1.09111 -0.00961441 -6.18967 0.00233809 0.00265332 -0.00271401 +EDGE3 1212 1263 -1.87388 12.2594 -6.31658 0.00157653 -0.00434533 0.118173 +EDGE3 1213 1262 -1.83439 -12.2697 -6.07915 -0.00280867 0.00871566 -0.124175 +EDGE3 1214 1264 -1.0987 -0.00877206 -6.20448 0.000767642 -0.00497041 -0.00185726 +EDGE3 1213 1264 -1.88466 12.2661 -6.31414 0.000460357 0.00609586 0.126159 +EDGE3 1214 1263 -1.827 -12.2607 -6.06063 -0.00481043 -0.000340906 -0.121319 +EDGE3 1215 1265 -1.08314 0.00762757 -6.19038 -0.00236598 -0.00647256 -0.00104305 +EDGE3 1214 1265 -1.87105 12.2643 -6.31362 0.00666331 0.00523199 0.12244 +EDGE3 1215 1264 -1.84349 -12.2711 -6.07067 -0.00243733 -0.00217267 -0.122715 +EDGE3 1216 1266 -1.09478 -0.00463532 -6.19459 -0.00904273 -0.0048407 -0.0028139 +EDGE3 1215 1266 -1.90051 12.2404 -6.30074 0.00410241 -0.000156571 0.128368 +EDGE3 1216 1265 -1.86132 -12.2745 -6.08004 0.00408617 0.00477359 -0.114533 +EDGE3 1217 1267 -1.10535 0.0139236 -6.18249 0.00502376 0.00250516 0.0031884 +EDGE3 1216 1267 -1.89451 12.235 -6.30547 -0.00239452 0.00321745 0.123634 +EDGE3 1217 1266 -1.85769 -12.2613 -6.05902 0.00929293 0.00148311 -0.125499 +EDGE3 1218 1268 -1.13341 0.0168396 -6.18031 -0.00191958 -0.00127183 -0.00198688 +EDGE3 1217 1268 -1.92365 12.2473 -6.30529 0.0022198 0.00231362 0.13381 +EDGE3 1218 1267 -1.86666 -12.2588 -6.07876 -0.00128407 -0.00436919 -0.128535 +EDGE3 1219 1269 -1.12169 -0.0108364 -6.18995 -0.000389061 -0.00135127 -0.00506213 +EDGE3 1218 1269 -1.92542 12.2496 -6.31181 -0.00309408 -0.00463105 0.136943 +EDGE3 1219 1268 -1.88867 -12.2364 -6.04839 -0.000866239 0.00342127 -0.127255 +EDGE3 1220 1270 -1.13858 -0.00411489 -6.16896 -0.00321739 -0.00578906 -0.00290691 +EDGE3 1219 1270 -1.94321 12.2434 -6.29829 0.00129743 0.00192137 0.115095 +EDGE3 1220 1269 -1.88274 -12.2541 -6.044 0.00361667 -0.00565734 -0.122567 +EDGE3 1221 1271 -1.14464 -0.0118791 -6.17439 0.0017851 -0.00228636 0.00238571 +EDGE3 1220 1271 -1.9391 12.236 -6.30188 0.00522051 0.00715627 0.123608 +EDGE3 1221 1270 -1.8811 -12.2514 -6.05135 -0.00901113 0.00683299 -0.131139 +EDGE3 1222 1272 -1.14702 0.00835665 -6.17428 -0.00201767 0.000469808 -0.00636336 +EDGE3 1221 1272 -1.94433 12.2351 -6.30181 0.00775178 0.00521698 0.129031 +EDGE3 1222 1271 -1.89865 -12.2583 -6.05882 -0.00102919 -0.000966689 -0.127156 +EDGE3 1223 1273 -1.17371 0.0060038 -6.17322 0.00369641 -0.00626277 -0.00108109 +EDGE3 1222 1273 -1.93962 12.2484 -6.31735 -0.00358253 -0.000116019 0.124343 +EDGE3 1223 1272 -1.92081 -12.2285 -6.05671 -0.0162591 0.00325434 -0.118824 +EDGE3 1224 1274 -1.15361 0.0125065 -6.18039 -0.00169667 0.00423324 -0.00585996 +EDGE3 1223 1274 -1.97487 12.2255 -6.29246 -0.0034531 0.00267028 0.127377 +EDGE3 1224 1273 -1.90266 -12.24 -6.05009 0.00697523 0.00442224 -0.12444 +EDGE3 1225 1275 -1.18331 -0.00874076 -6.17338 -0.00696206 0.00401516 0.00927983 +EDGE3 1224 1275 -1.9621 12.233 -6.30308 -0.00176359 -0.00228289 0.124519 +EDGE3 1225 1274 -1.9157 -12.2388 -6.05089 0.0100405 0.00127213 -0.130941 +EDGE3 1226 1276 -1.16514 0.00146596 -6.18837 0.00836612 -0.00154315 0.000498531 +EDGE3 1225 1276 -1.9772 12.2319 -6.29892 0.00276664 -0.0018002 0.122883 +EDGE3 1226 1275 -1.93158 -12.2399 -6.02457 0.00575992 0.000936377 -0.122232 +EDGE3 1227 1277 -1.18331 0.00594239 -6.17027 0.00168002 -0.00158513 0.00647278 +EDGE3 1226 1277 -1.96451 12.2158 -6.29634 -0.00034545 -0.00475471 0.122795 +EDGE3 1227 1276 -1.91374 -12.2221 -6.04779 -0.00321915 -0.00417287 -0.127122 +EDGE3 1228 1278 -1.19758 -0.00285214 -6.1541 0.00149302 0.00113628 -0.00430181 +EDGE3 1227 1278 -1.99137 12.2339 -6.28134 0.00878801 -0.0159384 0.131276 +EDGE3 1228 1277 -1.9253 -12.2317 -6.02268 0.000138531 0.00243892 -0.120581 +EDGE3 1229 1279 -1.19879 0.00389309 -6.15542 -5.2347e-05 -0.00408218 0.0039793 +EDGE3 1228 1279 -2.00587 12.2183 -6.27045 0.00348686 -0.00589381 0.121596 +EDGE3 1229 1278 -1.95774 -12.2234 -6.03662 0.000913849 0.00680407 -0.115628 +EDGE3 1230 1280 -1.22856 -0.0168639 -6.16801 0.00249322 -0.00367486 -0.00610038 +EDGE3 1229 1280 -1.99262 12.2191 -6.30148 -0.00408974 -0.000362377 0.125398 +EDGE3 1230 1279 -1.95023 -12.2046 -6.06046 -0.00530008 -0.00528074 -0.126404 +EDGE3 1231 1281 -1.21624 -0.00801326 -6.16293 0.00568207 0.00290833 -0.00509283 +EDGE3 1230 1281 -2.01498 12.2158 -6.29586 0.00403715 0.0035511 0.12374 +EDGE3 1231 1280 -1.96413 -12.2088 -6.04283 0.000665685 0.000793022 -0.117262 +EDGE3 1232 1282 -1.22118 -0.0118305 -6.16958 0.00242084 0.00312542 0.00559026 +EDGE3 1231 1282 -2.01717 12.2055 -6.2776 0.00385332 -0.00424741 0.12249 +EDGE3 1232 1281 -1.96298 -12.198 -6.03237 -0.00143891 0.0015397 -0.127541 +EDGE3 1233 1283 -1.2291 0.0122761 -6.15611 0.00235038 0.00424668 -0.00222943 +EDGE3 1232 1283 -2.01804 12.1985 -6.26552 -0.00592713 0.00322047 0.124302 +EDGE3 1233 1282 -1.98382 -12.1999 -6.04308 0.00643384 -0.000327816 -0.128581 +EDGE3 1234 1284 -1.24411 0.000547453 -6.16692 -0.00234368 -0.00446131 0.00517295 +EDGE3 1233 1284 -2.04346 12.2026 -6.27827 0.00769644 0.00294447 0.127361 +EDGE3 1234 1283 -1.98228 -12.2104 -6.02568 0.00576656 -0.000474741 -0.119634 +EDGE3 1235 1285 -1.25846 -0.0199646 -6.14654 -0.00631555 0.000547062 -0.00284981 +EDGE3 1234 1285 -2.0366 12.1922 -6.27048 -0.00119716 -0.00625033 0.124605 +EDGE3 1235 1284 -1.99315 -12.1949 -6.05176 4.15408e-05 -0.00079272 -0.126211 +EDGE3 1236 1286 -1.27018 0.000222362 -6.16443 -0.00952945 -0.0151464 -0.00280213 +EDGE3 1235 1286 -2.04396 12.2044 -6.26218 0.00982608 -0.00160672 0.122111 +EDGE3 1236 1285 -2.0032 -12.2021 -6.02577 -0.0024461 0.00376029 -0.12427 +EDGE3 1237 1287 -1.26505 -0.0150062 -6.14101 0.00856082 -0.00230722 -0.00196391 +EDGE3 1236 1287 -2.05473 12.1925 -6.30113 -0.000554669 0.00202528 0.133614 +EDGE3 1237 1286 -2.00354 -12.2032 -6.02624 -0.00135999 0.00975434 -0.131344 +EDGE3 1238 1288 -1.28944 -0.00470621 -6.15602 -0.0035996 -0.00757718 0.00498385 +EDGE3 1237 1288 -2.06631 12.1822 -6.26822 -0.00321739 0.00342101 0.121374 +EDGE3 1238 1287 -2.02472 -12.1779 -6.01642 -0.00436331 0.00326753 -0.122864 +EDGE3 1239 1289 -1.28066 0.00993117 -6.15701 -0.00368617 -0.00308197 -0.00498237 +EDGE3 1238 1289 -2.07073 12.19 -6.26735 0.00223921 0.00526294 0.121279 +EDGE3 1239 1288 -2.02504 -12.1737 -6.02208 0.00377636 0.00497753 -0.125195 +EDGE3 1240 1290 -1.28279 0.00134617 -6.14866 -0.00608044 -0.00253244 -0.00851474 +EDGE3 1239 1290 -2.074 12.1743 -6.28308 0.000749529 0.000330805 0.127833 +EDGE3 1240 1289 -2.0317 -12.1811 -6.02773 -0.00281243 -0.00673481 -0.122388 +EDGE3 1241 1291 -1.31583 -6.14079e-05 -6.13955 0.00326675 -0.0100391 0.00646376 +EDGE3 1240 1291 -2.06456 12.1748 -6.27352 -0.00109743 -0.00424295 0.118305 +EDGE3 1241 1290 -2.0336 -12.1889 -6.00968 -0.00270611 -0.0100466 -0.131889 +EDGE3 1242 1292 -1.30444 -0.0118768 -6.13677 -0.000505111 0.00434088 0.00393113 +EDGE3 1241 1292 -2.10023 12.1661 -6.26732 -0.000469047 0.00270923 0.121277 +EDGE3 1242 1291 -2.04919 -12.174 -6.01323 -0.000844905 -0.00106643 -0.127852 +EDGE3 1243 1293 -1.31129 0.00563454 -6.14438 0.00399283 0.00423763 -0.00168003 +EDGE3 1242 1293 -2.10361 12.1662 -6.26749 -0.00421995 -0.0177817 0.124474 +EDGE3 1243 1292 -2.04982 -12.1544 -6.01781 0.00149 -0.00440563 -0.121036 +EDGE3 1244 1294 -1.31709 -0.00687083 -6.15593 -0.00396446 -0.0029324 0.0037965 +EDGE3 1243 1294 -2.1009 12.1569 -6.26394 0.000768394 -0.000535804 0.127365 +EDGE3 1244 1293 -2.06812 -12.1688 -6.00591 -0.00519289 0.0012088 -0.122312 +EDGE3 1245 1295 -1.34037 0.00652716 -6.13633 0.00614232 0.00218485 0.00581452 +EDGE3 1244 1295 -2.11786 12.1493 -6.25509 -0.00578447 0.00372867 0.130179 +EDGE3 1245 1294 -2.07726 -12.1548 -6.02752 0.0030141 -0.00142089 -0.12282 +EDGE3 1246 1296 -1.33639 0.0134093 -6.14038 -0.00401677 0.00936825 -0.000461159 +EDGE3 1245 1296 -2.13878 12.1593 -6.26254 -0.00522006 -0.00131234 0.122195 +EDGE3 1246 1295 -2.06574 -12.1595 -6.005 0.000424218 -0.00192294 -0.120507 +EDGE3 1247 1297 -1.35412 -0.00325291 -6.12414 0.00335858 -0.00268119 -0.00631245 +EDGE3 1246 1297 -2.13529 12.1385 -6.25312 0.00359257 -0.00161698 0.120191 +EDGE3 1247 1296 -2.08062 -12.164 -6.007 0.00106704 0.000280806 -0.117932 +EDGE3 1248 1298 -1.35233 0.000291612 -6.12489 0.00170123 -0.0144593 0.000122918 +EDGE3 1247 1298 -2.12837 12.1457 -6.23816 -0.0084349 -0.000697213 0.132738 +EDGE3 1248 1297 -2.0863 -12.1747 -6.02457 -0.0010739 0.00701766 -0.132396 +EDGE3 1249 1299 -1.35318 0.00744235 -6.11775 -0.00580461 -0.00169409 0.001103 +EDGE3 1248 1299 -2.14842 12.1525 -6.25132 -0.000310301 -0.000699131 0.128637 +EDGE3 1249 1298 -2.0993 -12.1587 -6.02493 0.00043086 -0.0019789 -0.12557 +EDGE3 1250 1300 -1.37942 0.0151423 -6.13484 -0.00937957 0.00511074 -0.000813706 +EDGE3 1249 1300 -2.15075 12.1347 -6.25379 -0.00146478 -0.00157745 0.121385 +EDGE3 1250 1299 -2.11283 -12.1568 -6.00313 0.00432578 -0.00128353 -0.118984 +EDGE3 1251 1301 -1.37846 -0.000350633 -6.13117 -0.00168149 -0.00363873 -0.00392459 +EDGE3 1250 1301 -2.17019 12.1306 -6.24802 -0.00750885 -0.000575472 0.121108 +EDGE3 1251 1300 -2.12189 -12.1388 -6.00945 5.18724e-05 -0.00138 -0.116866 +EDGE3 1252 1302 -1.40555 -0.00222531 -6.13326 0.000538556 0.00364973 0.00413479 +EDGE3 1251 1302 -2.15406 12.153 -6.25025 0.00605685 -0.00550907 0.117702 +EDGE3 1252 1301 -2.10283 -12.1531 -6.01255 -0.00662142 0.00758138 -0.131594 +EDGE3 1253 1303 -1.40694 0.0134627 -6.11629 0.00482936 -0.00170619 0.00712515 +EDGE3 1252 1303 -2.17478 12.1365 -6.26123 0.0043719 0.00968412 0.128662 +EDGE3 1253 1302 -2.14163 -12.1177 -5.99595 -0.00360701 0.00332719 -0.116875 +EDGE3 1254 1304 -1.40976 0.0070358 -6.11956 -9.66299e-05 0.0102076 0.00480182 +EDGE3 1253 1304 -2.18112 12.1354 -6.23165 -0.000142355 0.000998488 0.131786 +EDGE3 1254 1303 -2.14081 -12.1402 -5.99492 0.00774031 -0.00149616 -0.130669 +EDGE3 1255 1305 -1.42094 0.00291775 -6.12517 0.000190237 -0.000375257 -0.00552713 +EDGE3 1254 1305 -2.2073 12.1187 -6.24335 0.00104601 -0.00514933 0.128043 +EDGE3 1255 1304 -2.15186 -12.1207 -6.01328 0.00839223 0.00349578 -0.12843 +EDGE3 1256 1306 -1.42105 -0.0115984 -6.13226 -0.0110806 0.00140196 -0.000830412 +EDGE3 1255 1306 -2.2118 12.1101 -6.23602 -0.00784496 -0.000743815 0.123149 +EDGE3 1256 1305 -2.15716 -12.1097 -5.99816 0.00293951 0.0110516 -0.129362 +EDGE3 1257 1307 -1.4295 -0.000681066 -6.11017 0.00634681 -0.00215732 0.00519381 +EDGE3 1256 1307 -2.1954 12.1028 -6.23405 -0.00707876 0.00224949 0.123109 +EDGE3 1258 1308 -1.43761 0.00459071 -6.10718 -0.0043448 0.0127841 -0.00494358 +EDGE3 1257 1306 -2.14915 -12.1182 -5.99308 0.00226786 0.000953503 -0.127209 +EDGE3 1257 1308 -2.22861 12.089 -6.22847 -0.000926303 -0.00338132 0.120358 +EDGE3 1258 1307 -2.17043 -12.1005 -5.99476 -0.00238094 -0.00485529 -0.12465 +EDGE3 1259 1309 -1.4409 -0.00182216 -6.11276 -0.00274354 -0.00373551 -0.00118229 +EDGE3 1258 1309 -2.24785 12.0904 -6.236 6.67365e-05 0.00723567 0.127557 +EDGE3 1259 1308 -2.15246 -12.1036 -5.99256 -0.000965259 -0.00246632 -0.125484 +EDGE3 1260 1310 -1.44398 -0.0133503 -6.11883 0.00317479 0.0075861 -0.0054342 +EDGE3 1259 1310 -2.24558 12.1133 -6.24137 -0.000589602 0.00409464 0.132188 +EDGE3 1261 1311 -1.45734 0.00600779 -6.12056 -0.00398036 0.00260343 -0.0034433 +EDGE3 1260 1309 -2.17664 -12.0878 -6.01317 0.00298838 -0.00235212 -0.125238 +EDGE3 1260 1311 -2.23831 12.0983 -6.22391 0.00949638 -0.00441574 0.12557 +EDGE3 1261 1310 -2.21328 -12.1124 -5.99043 -0.00433315 -0.00968734 -0.124835 +EDGE3 1261 1312 -2.24415 12.0804 -6.23819 -0.00356356 0.000939557 0.135699 +EDGE3 1262 1312 -1.44972 -0.0110206 -6.09281 0.0019977 0.00467761 0.00812821 +EDGE3 1263 1313 -1.47353 0.00101646 -6.09712 -0.000572981 -0.000188722 0.00524961 +EDGE3 1262 1311 -2.18364 -12.081 -5.97161 0.00746218 0.00509931 -0.120027 +EDGE3 1262 1313 -2.26123 12.0783 -6.21131 -0.00330616 0.0015646 0.126899 +EDGE3 1263 1312 -2.20526 -12.0924 -5.98741 0.0092469 0.000248713 -0.1294 +EDGE3 1264 1314 -1.47958 -0.00584973 -6.10019 3.02705e-05 0.00451208 -0.00309143 +EDGE3 1263 1314 -2.27829 12.0767 -6.22721 -0.00647477 0.00186124 0.122308 +EDGE3 1264 1313 -2.20524 -12.0967 -5.97025 -0.00640462 0.00369756 -0.12624 +EDGE3 1264 1315 -2.27583 12.0866 -6.23057 -0.00341038 0.00779401 0.128658 +EDGE3 1265 1315 -1.48777 0.0091003 -6.10271 0.00319431 0.00120349 0.0049289 +EDGE3 1266 1316 -1.50084 -0.00376698 -6.09813 0.00818154 -0.00491756 0.00482189 +EDGE3 1265 1314 -2.19319 -12.1017 -5.98519 -0.00038786 -0.0104403 -0.124903 +EDGE3 1265 1316 -2.27338 12.074 -6.23861 0.00460128 0.00414457 0.129045 +EDGE3 1266 1315 -2.21617 -12.0826 -5.96838 -0.00359898 0.00336519 -0.133058 +EDGE3 1267 1317 -1.49715 -0.00276979 -6.11344 0.00989139 0.00741322 -0.0016671 +EDGE3 1266 1317 -2.28964 12.0634 -6.23994 -0.00333484 -0.00393824 0.128328 +EDGE3 1267 1316 -2.22995 -12.0806 -6.00694 0.00054658 -0.00302717 -0.118556 +EDGE3 1268 1318 -1.50153 -0.00934452 -6.10131 0.000249297 0.00333808 0.00236405 +EDGE3 1267 1318 -2.31092 12.0779 -6.21988 -0.00864298 -0.00472854 0.123837 +EDGE3 1268 1317 -2.23278 -12.0406 -5.96993 -0.00342743 -0.00347145 -0.134521 +EDGE3 1268 1319 -2.30874 12.0589 -6.23223 0.00153403 -0.000171724 0.118817 +EDGE3 1269 1319 -1.50319 0.0141769 -6.11633 0.00133831 0.00929505 0.00772275 +EDGE3 1269 1318 -2.22564 -12.0662 -5.96651 -0.00459008 -0.000405658 -0.129487 +EDGE3 1270 1320 -1.5275 0.000202204 -6.10183 0.00706587 -0.00430586 -0.011852 +EDGE3 1269 1320 -2.3018 12.0768 -6.22607 0.000319115 -0.00198138 0.118729 +EDGE3 1270 1319 -2.23993 -12.0692 -5.98585 -0.000709333 -0.00844005 -0.122934 +EDGE3 1271 1321 -1.52954 0.00613655 -6.12232 -5.8557e-05 -0.00808747 -0.00187447 +EDGE3 1270 1321 -2.3095 12.0515 -6.22452 -0.002412 0.003136 0.119856 +EDGE3 1271 1320 -2.25838 -12.0526 -5.97479 -0.00220788 -0.0031448 -0.127302 +EDGE3 1272 1322 -1.56145 -0.00480953 -6.09284 -0.00278172 -0.0109717 -0.00335514 +EDGE3 1271 1322 -2.31738 12.0459 -6.21809 0.000914676 0.000140788 0.118537 +EDGE3 1273 1323 -1.53337 0.0102646 -6.08164 -0.00653184 0.00546746 -0.000700168 +EDGE3 1272 1321 -2.2687 -12.0488 -5.9678 0.000470836 -0.00607245 -0.132725 +EDGE3 1272 1323 -2.33551 12.0311 -6.23072 -0.00618778 0.00212377 0.129713 +EDGE3 1273 1322 -2.27763 -12.0352 -5.96667 0.0053364 -0.000747174 -0.126485 +EDGE3 1274 1324 -1.54091 0.000817357 -6.07772 -0.00605633 0.000294675 0.00431891 +EDGE3 1273 1324 -2.34835 12.0215 -6.22758 0.000542945 -0.00277123 0.117092 +EDGE3 1274 1323 -2.26783 -12.0358 -5.96988 -0.00271654 -0.00138657 -0.122558 +EDGE3 1274 1325 -2.35497 12.0033 -6.2107 0.00132606 -0.00611024 0.121075 +EDGE3 1275 1325 -1.5587 0.00614759 -6.08555 0.00804712 0.0031965 0.00448047 +EDGE3 1276 1326 -1.57658 0.00401627 -6.07418 0.000490823 -0.00382333 0.00655783 +EDGE3 1275 1324 -2.30018 -12.038 -5.94182 0.000171203 0.00032874 -0.123127 +EDGE3 1275 1326 -2.35695 12.0118 -6.19629 -0.00393793 -0.00795257 0.133065 +EDGE3 1276 1325 -2.29708 -12.0327 -5.96024 -0.00658664 -0.00157855 -0.123008 +EDGE3 1277 1327 -1.58984 3.00826e-05 -6.06857 -0.00274808 -0.00231439 0.00209328 +EDGE3 1276 1327 -2.34459 12.0135 -6.20425 -0.000143207 -8.19409e-05 0.122355 +EDGE3 1277 1326 -2.31439 -12.0338 -5.95164 0.00155841 0.0017382 -0.118541 +EDGE3 1278 1328 -1.59229 0.0150069 -6.06933 0.00368343 -0.000701584 -0.00170895 +EDGE3 1277 1328 -2.34664 12.0221 -6.20544 -0.00691473 0.00948792 0.129383 +EDGE3 1278 1327 -2.30175 -12.0324 -5.95158 -0.00764838 -0.00749032 -0.131261 +EDGE3 1279 1329 -1.58175 0.00141946 -6.07914 -0.0111587 -0.000899976 -7.1957e-05 +EDGE3 1278 1329 -2.38859 12.0118 -6.21624 -0.00201875 -0.0052995 0.127963 +EDGE3 1279 1328 -2.33874 -12.0115 -5.95145 0.000326289 -0.0025738 -0.135077 +EDGE3 1280 1330 -1.59796 -0.00742339 -6.07298 0.00747963 -0.00756291 0.00311896 +EDGE3 1279 1330 -2.37785 12.0116 -6.18952 0.0096843 0.00141551 0.129709 +EDGE3 1280 1329 -2.33645 -12.0332 -5.95123 0.00194766 0.000334106 -0.123968 +EDGE3 1281 1331 -1.62306 -0.00799634 -6.08019 0.00014948 -0.0125508 0.00212468 +EDGE3 1280 1331 -2.39275 11.9991 -6.19565 0.0120879 -0.00105182 0.12904 +EDGE3 1281 1330 -2.33677 -11.999 -5.94944 0.000471318 0.00317299 -0.130521 +EDGE3 1282 1332 -1.62028 -8.72218e-05 -6.07506 0.00185516 0.000757638 -7.01057e-05 +EDGE3 1281 1332 -2.40533 12.0035 -6.20692 0.00754218 0.00383978 0.118747 +EDGE3 1282 1331 -2.3288 -12.002 -5.93943 -0.0145985 -0.00274275 -0.127086 +EDGE3 1282 1333 -2.41501 11.998 -6.19774 0.00154167 -0.000414636 0.124857 +EDGE3 1283 1333 -1.62231 0.0146721 -6.09773 0.00305455 0.00576136 -0.0020391 +EDGE3 1284 1334 -1.65106 -0.0102057 -6.05991 -0.0053115 -0.00238632 0.00368596 +EDGE3 1283 1332 -2.33728 -12.0141 -5.95598 0.00181538 -0.000140374 -0.130294 +EDGE3 1283 1334 -2.41235 12.0027 -6.19628 -0.00822353 -0.00606917 0.127199 +EDGE3 1284 1333 -2.34506 -12.0103 -5.938 -0.00541812 -0.00497025 -0.132537 +EDGE3 1285 1335 -1.63721 0.00954581 -6.05108 0.00727057 0.0064704 -0.00198049 +EDGE3 1284 1335 -2.43496 11.9972 -6.18988 -0.00836 0.00590854 0.127608 +EDGE3 1285 1334 -2.34456 -12.0052 -5.94908 -0.00358037 0.0107971 -0.121157 +EDGE3 1286 1336 -1.63753 -0.00421474 -6.04801 0.00317879 -0.000811129 0.00334045 +EDGE3 1285 1336 -2.4403 11.9708 -6.18325 -0.00735558 -0.00223817 0.122772 +EDGE3 1286 1335 -2.36727 -12.0076 -5.9427 -0.00541697 -0.0090488 -0.137799 +EDGE3 1287 1337 -1.66452 0.03716 -6.04646 0.000735507 -0.000593098 0.00612003 +EDGE3 1286 1337 -2.43665 12.0005 -6.18643 -0.000791997 -0.000535018 0.131089 +EDGE3 1287 1336 -2.36762 -11.9931 -5.92606 -0.00795122 -0.00179453 -0.126679 +EDGE3 1288 1338 -1.66573 -0.00601106 -6.07448 -0.00318751 0.00488577 -0.00303404 +EDGE3 1287 1338 -2.44622 11.9681 -6.18621 -0.00447479 -0.00546236 0.119286 +EDGE3 1288 1337 -2.38052 -11.9894 -5.93991 -0.00341111 -0.0035226 -0.119877 +EDGE3 1289 1339 -1.67321 -0.00599371 -6.07106 -0.00616076 -0.000454494 -0.00659816 +EDGE3 1288 1339 -2.45765 11.9893 -6.15936 0.000939473 -0.00320556 0.127029 +EDGE3 1289 1338 -2.38507 -11.9909 -5.92491 0.000188746 0.00243447 -0.121011 +EDGE3 1290 1340 -1.66223 -0.00766776 -6.04287 0.00285241 -0.00187795 0.00302848 +EDGE3 1289 1340 -2.46265 11.9732 -6.18715 0.00395238 0.00520042 0.123825 +EDGE3 1290 1339 -2.38439 -11.9732 -5.93962 -0.0071926 3.07388e-05 -0.115829 +EDGE3 1291 1341 -1.68531 0.0133967 -6.03859 0.000729536 0.00576483 0.00147798 +EDGE3 1290 1341 -2.4416 11.9562 -6.17604 0.00380665 0.00878932 0.120654 +EDGE3 1291 1340 -2.38928 -11.964 -5.92338 -0.0064761 -0.00210947 -0.130841 +EDGE3 1292 1342 -1.68766 0.0133976 -6.05027 -0.000489278 -0.00513934 0.0041362 +EDGE3 1291 1342 -2.47442 11.9546 -6.16864 -0.0124541 0.00298216 0.122372 +EDGE3 1292 1341 -2.41221 -11.9702 -5.92769 -0.00178072 -0.00292831 -0.121789 +EDGE3 1293 1343 -1.69025 0.0146882 -6.04436 -0.00135414 -0.000111591 0.00130123 +EDGE3 1292 1343 -2.49785 11.9624 -6.17812 -0.00431373 0.00160997 0.129042 +EDGE3 1293 1342 -2.41509 -11.9431 -5.94178 0.00164927 -0.000792807 -0.134956 +EDGE3 1294 1344 -1.70121 0.00131409 -6.04345 0.00925854 -0.013055 0.000942711 +EDGE3 1293 1344 -2.49743 11.939 -6.1646 -0.00257235 0.00161158 0.129183 +EDGE3 1294 1343 -2.42336 -11.9498 -5.93086 0.000238883 0.000890428 -0.127615 +EDGE3 1295 1345 -1.71894 -0.00391819 -6.06344 -8.89785e-06 -0.00353461 -0.00677507 +EDGE3 1294 1345 -2.49849 11.9535 -6.17641 0.00428347 -0.00205208 0.128081 +EDGE3 1295 1344 -2.4207 -11.961 -5.93387 -0.00239371 0.00120947 -0.130391 +EDGE3 1296 1346 -1.72018 0.00946666 -6.04734 -0.00305978 0.00601013 -0.00172191 +EDGE3 1295 1346 -2.5122 11.9547 -6.17181 0.000661366 -0.00329964 0.12125 +EDGE3 1296 1345 -2.42735 -11.9418 -5.93571 0.00362645 -0.00229236 -0.125073 +EDGE3 1297 1347 -1.7257 -0.0071358 -6.0347 0.00155559 -0.00498411 0.00725145 +EDGE3 1296 1347 -2.51045 11.9172 -6.17198 0.00124584 0.000524956 0.121647 +EDGE3 1297 1346 -2.45073 -11.9297 -5.91915 0.00097152 0.00256432 -0.129202 +EDGE3 1298 1348 -1.74303 0.00526137 -6.03296 0.00476063 -0.0012479 -0.00372027 +EDGE3 1297 1348 -2.51429 11.9267 -6.14523 0.00228167 0.00200698 0.130112 +EDGE3 1298 1347 -2.44781 -11.9526 -5.91614 -0.00348542 -0.0019382 -0.135149 +EDGE3 1299 1349 -1.74693 0.00921731 -6.03427 -0.0120259 0.0147114 0.00164735 +EDGE3 1298 1349 -2.52865 11.9197 -6.16475 -0.000464738 -0.00658666 0.122406 +EDGE3 1299 1348 -2.44712 -11.9388 -5.93204 0.0088224 -0.00227875 -0.111424 +EDGE3 1300 1350 -1.75371 0.0129269 -6.03403 0.00158358 -0.00081 0.0032821 +EDGE3 1299 1350 -2.53421 11.9089 -6.16576 -0.00973236 -0.00319772 0.121914 +EDGE3 1300 1349 -2.47756 -11.9262 -5.91336 -0.00016288 -0.0117434 -0.126914 +EDGE3 1301 1351 -1.78171 -0.0066518 -6.01064 0.000541027 -0.00827982 0.00687067 +EDGE3 1300 1351 -2.54769 11.9161 -6.14625 0.00445508 0.00254884 0.116812 +EDGE3 1301 1350 -2.46925 -11.9 -5.9 0.0077249 -0.00278785 -0.117734 +EDGE3 1302 1352 -1.77809 -0.0198924 -6.02306 -0.00188075 -0.005498 -0.00337847 +EDGE3 1301 1352 -2.53261 11.9081 -6.15507 -0.0108137 -0.00271034 0.12752 +EDGE3 1302 1351 -2.46261 -11.931 -5.90677 -0.00104695 -0.00286695 -0.126841 +EDGE3 1303 1353 -1.77421 -0.000720837 -6.0275 -0.00161205 -0.000382982 0.00816154 +EDGE3 1302 1353 -2.55889 11.902 -6.12721 -0.00376901 -0.0027801 0.128155 +EDGE3 1303 1352 -2.48205 -11.9048 -5.89978 -0.00444734 -0.00211646 -0.131889 +EDGE3 1304 1354 -1.79916 0.00423345 -6.01537 -0.00302115 0.0027325 -0.00963069 +EDGE3 1303 1354 -2.55779 11.8924 -6.14165 -0.00254435 0.00626875 0.122067 +EDGE3 1304 1353 -2.51619 -11.9014 -5.88231 0.00794002 -0.000243216 -0.134041 +EDGE3 1305 1355 -1.80318 5.36478e-05 -6.02597 0.00418759 0.000213165 0.00731267 +EDGE3 1304 1355 -2.58044 11.8954 -6.12945 -0.0028399 0.00755985 0.136765 +EDGE3 1305 1354 -2.50311 -11.8876 -5.9178 0.00183962 0.00828727 -0.120411 +EDGE3 1306 1356 -1.78864 -0.0038653 -6.01843 0.00700442 -0.00695609 0.00584936 +EDGE3 1305 1356 -2.58291 11.8912 -6.13133 0.00483228 -0.0019554 0.122837 +EDGE3 1306 1355 -2.50982 -11.881 -5.90084 0.00213121 -0.00465355 -0.123658 +EDGE3 1307 1357 -1.80885 -0.00664941 -6.02121 -0.00536365 0.00638962 -0.000416983 +EDGE3 1306 1357 -2.58265 11.8827 -6.14632 -0.00042139 -0.00549883 0.132412 +EDGE3 1307 1356 -2.52989 -11.8891 -5.90323 -0.00222472 -0.000802468 -0.122778 +EDGE3 1308 1358 -1.8095 0.0026296 -6.02621 -0.00217093 0.0107824 0.000241181 +EDGE3 1307 1358 -2.58655 11.8775 -6.12781 0.00311644 0.00199054 0.1258 +EDGE3 1308 1357 -2.5262 -11.8923 -5.90686 -0.00063681 -0.00087927 -0.116956 +EDGE3 1309 1359 -1.80976 0.00739359 -6.01778 0.00371392 0.00597432 0.00377424 +EDGE3 1308 1359 -2.59711 11.8763 -6.1471 -0.0110076 -0.00361975 0.114907 +EDGE3 1309 1358 -2.53031 -11.8848 -5.89454 -0.0121089 -0.00610809 -0.118418 +EDGE3 1310 1360 -1.82527 0.0190463 -5.99818 -0.00139675 -0.010531 -0.00460139 +EDGE3 1309 1360 -2.61192 11.8631 -6.13534 -0.0095887 0.0061446 0.12836 +EDGE3 1310 1359 -2.54105 -11.8705 -5.8951 -0.00187179 0.00267709 -0.113221 +EDGE3 1311 1361 -1.83318 -0.00631814 -5.99326 -0.000825265 0.00420988 0.000221901 +EDGE3 1310 1361 -2.61708 11.8722 -6.14297 0.00397209 -0.0038316 0.126145 +EDGE3 1311 1360 -2.52782 -11.8717 -5.88694 -0.00272966 0.0056701 -0.128998 +EDGE3 1312 1362 -1.84696 -0.00523842 -6.01816 -0.00364537 -0.00516287 0.00167897 +EDGE3 1311 1362 -2.63324 11.8525 -6.1302 0.00108359 0.00084881 0.125288 +EDGE3 1312 1361 -2.55155 -11.8741 -5.87788 -0.0036631 -0.00131576 -0.12652 +EDGE3 1313 1363 -1.85839 0.00789332 -6.00963 0.00600651 0.00580216 -0.00605588 +EDGE3 1312 1363 -2.6281 11.8694 -6.11573 0.00217007 -0.00129061 0.120771 +EDGE3 1313 1362 -2.55814 -11.8625 -5.87272 0.00527217 -0.00647406 -0.119997 +EDGE3 1314 1364 -1.86689 0.00716934 -5.97973 -0.000850539 -0.00546238 0.0108753 +EDGE3 1313 1364 -2.62569 11.8586 -6.12541 -0.00459027 -0.00641495 0.125858 +EDGE3 1314 1363 -2.54088 -11.8496 -5.87007 0.00461091 -0.000150298 -0.129973 +EDGE3 1315 1365 -1.86286 -0.00616268 -5.99338 0.00145637 0.00338557 -0.00569419 +EDGE3 1314 1365 -2.66726 11.8531 -6.11111 -0.00581086 -0.0018703 0.122607 +EDGE3 1315 1364 -2.56683 -11.8574 -5.86834 0.00847801 -0.00548614 -0.129981 +EDGE3 1316 1366 -1.88098 -0.00282237 -6.01335 -2.47839e-05 -0.00123034 0.00575307 +EDGE3 1315 1366 -2.6487 11.8449 -6.09557 0.00309447 -0.00283814 0.131986 +EDGE3 1316 1365 -2.56373 -11.8351 -5.84998 -0.00332312 -0.00197341 -0.116672 +EDGE3 1317 1367 -1.88879 0.0143499 -6.00996 6.82173e-05 0.00436986 2.86247e-05 +EDGE3 1316 1367 -2.65734 11.8384 -6.11558 0.00126667 -0.000540804 0.124981 +EDGE3 1317 1366 -2.59234 -11.8461 -5.87185 -0.00113643 0.00116381 -0.129374 +EDGE3 1318 1368 -1.87554 0.007359 -5.99264 -0.00805397 0.00630289 -0.003966 +EDGE3 1317 1368 -2.65323 11.8349 -6.13222 -0.00735887 0.00824941 0.138 +EDGE3 1318 1367 -2.60315 -11.8343 -5.86376 -0.00201128 0.00464356 -0.124199 +EDGE3 1319 1369 -1.92 0.00426302 -5.99042 -0.00160949 0.000212093 -0.00188433 +EDGE3 1318 1369 -2.67426 11.8265 -6.11172 -0.00665069 0.0111154 0.124088 +EDGE3 1319 1368 -2.59544 -11.8276 -5.86826 0.00457307 -0.00218169 -0.122518 +EDGE3 1320 1370 -1.90568 -0.00993958 -5.98935 -0.00536499 0.00209453 0.00401445 +EDGE3 1319 1370 -2.68671 11.8009 -6.10901 -0.00353979 -0.00844318 0.124858 +EDGE3 1320 1369 -2.59493 -11.8225 -5.85077 0.00296225 -0.00333627 -0.13219 +EDGE3 1321 1371 -1.89516 0.000702676 -5.99344 0.00011751 -0.00278936 -0.000603697 +EDGE3 1320 1371 -2.69007 11.8132 -6.10964 0.000805738 -0.00368312 0.125685 +EDGE3 1321 1370 -2.601 -11.8129 -5.86248 0.000881011 -0.00555493 -0.126598 +EDGE3 1322 1372 -1.90741 -0.00249263 -5.9909 -0.0114209 0.000337295 0.00644336 +EDGE3 1321 1372 -2.70271 11.7985 -6.08914 0.00368769 -0.000486535 0.128784 +EDGE3 1322 1371 -2.62884 -11.813 -5.87147 -0.00326796 0.000202365 -0.125082 +EDGE3 1323 1373 -1.92135 0.0181157 -5.98056 -0.000794109 0.00582665 0.014451 +EDGE3 1322 1373 -2.70266 11.8182 -6.1169 0.00511262 -0.000557783 0.128661 +EDGE3 1323 1372 -2.62706 -11.8234 -5.85776 0.00204911 0.00171603 -0.119465 +EDGE3 1324 1374 -1.91219 0.000561141 -5.97128 -3.96712e-06 -0.00373292 -0.00370371 +EDGE3 1323 1374 -2.72181 11.8104 -6.10299 -0.00168496 -0.00220938 0.123399 +EDGE3 1324 1373 -2.66157 -11.8175 -5.85705 -0.0035981 0.00451443 -0.13753 +EDGE3 1325 1375 -1.95336 -0.0104498 -5.96997 0.00584897 0.000273552 0.00244025 +EDGE3 1324 1375 -2.71507 11.7903 -6.10181 0.00169681 0.00458568 0.135426 +EDGE3 1325 1374 -2.64381 -11.8031 -5.86397 -0.00326425 0.000248316 -0.127306 +EDGE3 1326 1376 -1.9523 0.00619619 -5.98098 -0.00586305 0.00205231 0.00192867 +EDGE3 1325 1376 -2.7141 11.7802 -6.08705 0.00185912 -0.00346456 0.118351 +EDGE3 1326 1375 -2.63781 -11.7946 -5.85435 0.00299786 0.00308035 -0.13059 +EDGE3 1327 1377 -1.9507 -0.00356787 -5.97097 -0.00309336 -0.0018444 -0.00364397 +EDGE3 1326 1377 -2.73072 11.8004 -6.09608 -0.00435734 0.0045611 0.120893 +EDGE3 1327 1376 -2.65323 -11.7886 -5.86795 -0.000655902 -0.00879365 -0.129187 +EDGE3 1328 1378 -1.96364 0.00334844 -5.97069 0.00347913 -0.000122212 0.00578368 +EDGE3 1328 1377 -2.68039 -11.7754 -5.85235 0.00581906 -0.00237116 -0.120349 +EDGE3 1327 1378 -2.74298 11.7787 -6.08593 -0.00184629 -0.00042 0.118805 +EDGE3 1329 1379 -1.97112 0.00587674 -5.96695 -0.0039159 0.00267405 -0.00838057 +EDGE3 1328 1379 -2.74947 11.7672 -6.08142 -0.00167645 0.00225033 0.124422 +EDGE3 1329 1378 -2.65146 -11.7615 -5.82663 0.00797255 0.00160008 -0.127269 +EDGE3 1330 1380 -1.9756 -0.000234442 -5.96984 0.00117785 -6.74639e-06 0.00232422 +EDGE3 1329 1380 -2.76736 11.7685 -6.07858 0.00277419 -0.000375039 0.125883 +EDGE3 1330 1379 -2.67463 -11.7941 -5.85277 -0.000498387 0.00123012 -0.126402 +EDGE3 1331 1381 -1.97656 -0.00428971 -5.95455 -0.00422569 0.00588883 0.00512675 +EDGE3 1330 1381 -2.76611 11.7718 -6.08092 0.00118819 -0.00465108 0.135608 +EDGE3 1331 1380 -2.70134 -11.7567 -5.84677 0.00162602 0.000657535 -0.127434 +EDGE3 1332 1382 -1.99226 -0.00521253 -5.94292 -3.68194e-06 -8.74505e-05 -0.00561228 +EDGE3 1331 1382 -2.79161 11.7662 -6.0595 -0.00232441 -0.0016582 0.126776 +EDGE3 1332 1381 -2.6919 -11.7495 -5.84331 -0.00274974 -0.000872446 -0.118032 +EDGE3 1333 1383 -2.00285 -0.0150332 -5.9561 -0.00223918 -0.0071941 -0.00185312 +EDGE3 1332 1383 -2.77841 11.7382 -6.07482 0.00825324 -0.007194 0.120698 +EDGE3 1333 1382 -2.69186 -11.749 -5.83407 -0.000991503 -0.0031569 -0.12721 +EDGE3 1334 1384 -2.00792 -0.00654286 -5.95637 -0.00313366 0.00669483 -0.00331202 +EDGE3 1333 1384 -2.76714 11.7273 -6.07346 -0.00243674 -0.00255995 0.124142 +EDGE3 1334 1383 -2.73178 -11.7542 -5.82979 -0.0053649 -0.00245217 -0.122385 +EDGE3 1335 1385 -2.02371 -0.000803676 -5.95378 -0.000461982 0.00344098 0.00509963 +EDGE3 1334 1385 -2.77345 11.7379 -6.06893 0.00687554 0.00404594 0.122015 +EDGE3 1335 1384 -2.72512 -11.7542 -5.83312 0.00405165 -0.00152516 -0.122213 +EDGE3 1336 1386 -2.01437 0.0151906 -5.93902 0.00392475 -0.00277011 -0.00560376 +EDGE3 1335 1386 -2.80271 11.7344 -6.087 -0.00753537 0.0063636 0.120834 +EDGE3 1336 1385 -2.7197 -11.7387 -5.82854 -0.00751585 0.00372245 -0.125914 +EDGE3 1337 1387 -2.04649 -0.0223202 -5.93376 -0.00195848 -0.00229445 -0.00475436 +EDGE3 1336 1387 -2.81113 11.7324 -6.06248 0.00824644 0.012429 0.126691 +EDGE3 1337 1386 -2.72356 -11.7293 -5.82517 -0.00457621 0.00684741 -0.119352 +EDGE3 1338 1388 -2.03789 -0.00118052 -5.94869 0.0034073 0.000900248 -0.00241925 +EDGE3 1337 1388 -2.82253 11.7214 -6.05366 -0.00392174 -0.000606465 0.122555 +EDGE3 1338 1387 -2.72173 -11.7273 -5.83909 0.000435962 0.00176043 -0.129607 +EDGE3 1339 1389 -2.04563 -0.00379647 -5.92873 -0.00402886 -0.00460716 -0.00763104 +EDGE3 1338 1389 -2.81278 11.7195 -6.05588 -0.00475655 -0.00192255 0.130461 +EDGE3 1339 1388 -2.7315 -11.7186 -5.83007 0.00440874 0.00647302 -0.132351 +EDGE3 1340 1390 -2.04521 0.00528209 -5.93915 -0.00970801 0.00328361 0.00452302 +EDGE3 1339 1390 -2.83 11.7257 -6.05214 0.00249097 -0.00425697 0.132146 +EDGE3 1340 1389 -2.7398 -11.7184 -5.80344 -0.0113432 0.00494857 -0.12561 +EDGE3 1341 1391 -2.06691 0.0125113 -5.92515 0.00221863 0.00228938 0.00428394 +EDGE3 1340 1391 -2.82712 11.7005 -6.05398 0.00454004 0.003363 0.130849 +EDGE3 1341 1390 -2.75494 -11.7073 -5.83017 -0.00145211 -0.000676604 -0.133932 +EDGE3 1342 1392 -2.07116 0.00584584 -5.92597 0.00155962 0.0062573 -0.00114101 +EDGE3 1342 1391 -2.75102 -11.6898 -5.81138 0.00432385 0.00761373 -0.125052 +EDGE3 1341 1392 -2.83056 11.7163 -6.04172 0.000439684 -0.00295652 0.128391 +EDGE3 1343 1393 -2.06436 -0.00327793 -5.92946 0.0072076 -0.00309323 -0.00758243 +EDGE3 1342 1393 -2.84925 11.6837 -6.06082 0.000341668 0.00992917 0.130351 +EDGE3 1343 1392 -2.76461 -11.6979 -5.82007 -0.00292462 -0.00486006 -0.129026 +EDGE3 1344 1394 -2.09386 -0.0100269 -5.92398 0.0057232 -0.00990366 0.00623911 +EDGE3 1343 1394 -2.87123 11.6756 -6.0508 0.000320383 -0.000989939 0.123428 +EDGE3 1344 1393 -2.77157 -11.6915 -5.80396 -0.00478957 -0.00031673 -0.119558 +EDGE3 1345 1395 -2.09968 -0.00362463 -5.91458 -0.0117057 0.00116366 0.00134062 +EDGE3 1344 1395 -2.84155 11.6731 -6.03879 -0.00115513 0.00165421 0.121675 +EDGE3 1345 1394 -2.7791 -11.6797 -5.80611 0.0144007 -0.000968051 -0.124029 +EDGE3 1346 1396 -2.09414 0.000818578 -5.91595 -0.000865935 0.0118625 -0.00462524 +EDGE3 1345 1396 -2.87124 11.6882 -6.04901 -8.80124e-05 -0.00208955 0.122426 +EDGE3 1346 1395 -2.82714 -11.666 -5.79224 -0.00268124 -0.00278076 -0.129708 +EDGE3 1346 1397 -2.88291 11.6641 -6.02422 0.0013857 -0.00823265 0.12932 +EDGE3 1347 1397 -2.1015 0.0046303 -5.93558 -0.00321993 0.00594853 -0.0123697 +EDGE3 1348 1398 -2.12157 -0.0144109 -5.89499 -0.0025709 0.00762666 0.00356397 +EDGE3 1347 1396 -2.80229 -11.6668 -5.80272 0.00652274 -5.63367e-05 -0.129803 +EDGE3 1347 1398 -2.87632 11.6686 -6.04372 -0.00605976 -0.00504481 0.125911 +EDGE3 1348 1397 -2.80169 -11.6905 -5.79807 -0.0027048 -0.00332164 -0.1263 +EDGE3 1348 1399 -2.90374 11.6401 -6.02051 -0.00482951 0.0041297 0.128906 +EDGE3 1349 1399 -2.12805 0.00644287 -5.89733 0.00251844 0.0008211 0.00361783 +EDGE3 1350 1400 -2.11262 -0.00546088 -5.92493 0.000128981 0.00240493 0.0022324 +EDGE3 1349 1398 -2.808 -11.6633 -5.80537 0.00216091 -0.000634407 -0.131084 +EDGE3 1349 1400 -2.92151 11.6526 -6.02526 -0.0063297 0.00277695 0.124916 +EDGE3 1350 1399 -2.78708 -11.6526 -5.78593 0.00261574 0.00314739 -0.128748 +EDGE3 1351 1401 -2.13716 0.0093222 -5.91241 -0.00109008 -0.00415744 0.0114081 +EDGE3 1350 1401 -2.91536 11.6387 -6.03576 0.00775507 0.00163024 0.133593 +EDGE3 1351 1400 -2.83417 -11.6534 -5.79806 -0.00356875 -0.000833378 -0.119376 +EDGE3 1352 1402 -2.1433 0.000872605 -5.93506 0.000789439 -0.000865031 0.00130616 +EDGE3 1351 1402 -2.91779 11.6405 -6.01816 0.00532386 0.00262071 0.124873 +EDGE3 1353 1403 -2.12489 -0.00940154 -5.88427 -0.00694076 0.00350586 -0.0060922 +EDGE3 1352 1401 -2.82409 -11.6605 -5.79831 0.000234407 -0.00434593 -0.135025 +EDGE3 1352 1403 -2.92212 11.6455 -6.01235 0.000982116 0.00604519 0.12476 +EDGE3 1353 1402 -2.8532 -11.6497 -5.784 0.00624824 -0.00446767 -0.131204 +EDGE3 1354 1404 -2.17863 9.0428e-05 -5.8798 0.000215415 -0.00210563 0.00613158 +EDGE3 1353 1404 -2.92264 11.6394 -6.02196 -0.0116512 -0.000398446 0.117838 +EDGE3 1354 1403 -2.85704 -11.6432 -5.78971 0.000391569 -0.000824934 -0.126734 +EDGE3 1355 1405 -2.1516 -0.0147218 -5.90084 0.00343109 0.0063127 0.00737831 +EDGE3 1354 1405 -2.94019 11.6375 -6.02167 0.00229474 0.0112246 0.12616 +EDGE3 1356 1406 -2.18126 0.0126154 -5.89749 0.00374579 -0.00443616 0.00168948 +EDGE3 1355 1404 -2.86322 -11.6303 -5.79425 0.00764007 0.00298421 -0.128607 +EDGE3 1355 1406 -2.93553 11.624 -6.02992 -0.00233677 0.00390463 0.1225 +EDGE3 1356 1405 -2.83889 -11.6141 -5.77702 -0.00512887 -0.000541271 -0.126224 +EDGE3 1357 1407 -2.17991 0.0134252 -5.90523 -0.00256871 0.000145256 0.00508844 +EDGE3 1356 1407 -2.93237 11.5981 -6.03117 0.00274127 0.00529651 0.132836 +EDGE3 1358 1408 -2.18872 -0.00228052 -5.88487 -0.0027026 -0.00665966 0.00636758 +EDGE3 1357 1406 -2.86015 -11.6202 -5.76883 -0.00401397 0.00592184 -0.120555 +EDGE3 1357 1408 -2.96955 11.6213 -6.02578 0.00354577 -0.00236054 0.129368 +EDGE3 1358 1407 -2.87876 -11.6086 -5.78385 -0.00210721 0.00349227 -0.126249 +EDGE3 1359 1409 -2.20008 -0.0124321 -5.87741 -0.00863848 0.00527722 0.00332043 +EDGE3 1358 1409 -2.95622 11.6125 -6.01495 -0.00113285 -0.000177207 0.12553 +EDGE3 1359 1408 -2.87993 -11.6155 -5.78151 -0.00924941 0.00167207 -0.121345 +EDGE3 1360 1410 -2.19353 -0.00566224 -5.87433 -0.00712543 -0.00403773 -0.000983106 +EDGE3 1359 1410 -2.96248 11.6051 -6.00614 -0.00748837 -0.00843276 0.123683 +EDGE3 1360 1409 -2.87574 -11.5993 -5.7686 0.00321667 0.0108476 -0.12876 +EDGE3 1361 1411 -2.23036 0.0190374 -5.88449 -0.00111954 -0.00737939 -0.00193445 +EDGE3 1360 1411 -2.98919 11.5715 -6.00921 0.00351272 0.00496397 0.124824 +EDGE3 1361 1410 -2.89253 -11.6028 -5.756 0.00817314 0.00285071 -0.127398 +EDGE3 1362 1412 -2.22146 -0.0194989 -5.88356 0.00409714 -0.00493205 -0.00424306 +EDGE3 1361 1412 -3.00803 11.5859 -5.99752 0.00259232 -0.00241496 0.124977 +EDGE3 1362 1411 -2.91271 -11.603 -5.75452 -0.00221508 0.00333959 -0.129926 +EDGE3 1363 1413 -2.22006 -0.00057697 -5.86404 -0.00602973 -0.00510602 -0.00698489 +EDGE3 1362 1413 -2.97345 11.5598 -6.00867 0.00130372 0.00318301 0.125548 +EDGE3 1363 1412 -2.9149 -11.5769 -5.79065 0.000565824 0.00430325 -0.122944 +EDGE3 1364 1414 -2.22791 -0.00812218 -5.8723 0.00244966 -0.00282358 0.00217579 +EDGE3 1363 1414 -3.00016 11.5582 -5.97633 -0.00629633 0.00116891 0.132794 +EDGE3 1364 1413 -2.90075 -11.5643 -5.74563 0.000837549 0.00209663 -0.124855 +EDGE3 1365 1415 -2.22761 0.00527864 -5.87439 0.00859264 -0.00781837 0.00472893 +EDGE3 1364 1415 -3.00268 11.552 -6.00492 0.0040985 -2.85631e-05 0.124498 +EDGE3 1365 1414 -2.93298 -11.5777 -5.74804 -0.00585783 -0.00415869 -0.140685 +EDGE3 1366 1416 -2.26805 -0.00441978 -5.85115 0.00884662 0.00735493 -0.00179339 +EDGE3 1365 1416 -3.01311 11.5507 -5.9761 0.0036449 0.00247152 0.125172 +EDGE3 1366 1415 -2.91907 -11.5518 -5.75654 -0.00278908 -0.00679583 -0.123074 +EDGE3 1367 1417 -2.24451 0.00301652 -5.87698 -0.00487798 -0.00434163 0.0036326 +EDGE3 1366 1417 -3.028 11.5604 -5.99311 0.00335944 -0.00292971 0.119826 +EDGE3 1367 1416 -2.94021 -11.5614 -5.7552 0.00410871 0.000836068 -0.129742 +EDGE3 1368 1418 -2.2677 -0.00956328 -5.86489 -6.12128e-05 -0.00228297 -0.000610906 +EDGE3 1367 1418 -3.03899 11.5531 -5.97473 -0.00191716 -0.00115322 0.118641 +EDGE3 1368 1417 -2.94269 -11.5571 -5.72579 0.00313035 0.00409602 -0.129472 +EDGE3 1369 1419 -2.26965 -0.00535092 -5.87749 0.00741453 -0.004368 0.000730071 +EDGE3 1368 1419 -3.0564 11.5337 -5.95739 -0.0060529 0.00143464 0.122211 +EDGE3 1369 1418 -2.9594 -11.5529 -5.74436 -0.0037783 -0.00844506 -0.127529 +EDGE3 1370 1420 -2.27081 -0.0182855 -5.84897 -0.00280852 -0.00182251 -0.00452195 +EDGE3 1369 1420 -3.05023 11.5285 -5.95957 -0.0111375 0.000632127 0.127047 +EDGE3 1370 1419 -2.93842 -11.5352 -5.73931 -0.00357588 0.000975737 -0.133374 +EDGE3 1371 1421 -2.28639 0.0110967 -5.84945 -0.00171443 -0.00191537 -0.00619632 +EDGE3 1370 1421 -3.05522 11.5197 -5.98805 -0.00145345 0.00265242 0.126571 +EDGE3 1371 1420 -2.96977 -11.5288 -5.72642 0.00202372 0.00149381 -0.12769 +EDGE3 1371 1422 -3.06028 11.5165 -5.96884 0.0104185 -0.00020839 0.129747 +EDGE3 1372 1422 -2.29699 0.00564388 -5.855 0.00167644 0.000264891 0.00310118 +EDGE3 1373 1423 -2.30515 0.00246983 -5.84793 -0.00584291 -0.00046039 0.00224554 +EDGE3 1372 1421 -2.98081 -11.5315 -5.72843 -0.000587863 0.00190556 -0.118693 +EDGE3 1372 1423 -3.06798 11.5128 -5.98532 0.00239842 0.00498132 0.114866 +EDGE3 1373 1422 -2.94534 -11.5177 -5.73969 0.00270589 0.0016075 -0.124978 +EDGE3 1374 1424 -2.31693 -0.00584871 -5.84466 -0.00175873 -0.00081418 -0.00279947 +EDGE3 1373 1424 -3.07531 11.516 -5.9742 -0.00611242 0.0048255 0.116612 +EDGE3 1374 1423 -2.97052 -11.5248 -5.73316 -0.00124299 -0.00623382 -0.131919 +EDGE3 1375 1425 -2.31307 8.23211e-05 -5.84543 0.00477918 0.00322486 -0.00573443 +EDGE3 1374 1425 -3.09376 11.5058 -5.96655 -0.00318943 0.00271303 0.132773 +EDGE3 1375 1424 -2.9764 -11.5052 -5.71285 -0.00491987 0.000999752 -0.120688 +EDGE3 1376 1426 -2.32691 0.00902051 -5.84959 -0.015004 0.00130273 -0.00796014 +EDGE3 1375 1426 -3.08254 11.4851 -5.97045 0.000113461 -0.00410603 0.126669 +EDGE3 1376 1425 -2.9957 -11.4958 -5.71011 0.000913137 -0.00182414 -0.127739 +EDGE3 1377 1427 -2.32941 0.0180245 -5.8209 0.00907119 0.000541622 0.00269123 +EDGE3 1376 1427 -3.09372 11.4707 -5.94013 -0.00054162 0.0015595 0.123743 +EDGE3 1377 1426 -3.01481 -11.4845 -5.72809 0.00735579 0.0048362 -0.126035 +EDGE3 1378 1428 -2.31561 -0.00428788 -5.84209 -0.00673357 0.0016468 0.00174353 +EDGE3 1377 1428 -3.10771 11.4796 -5.9416 0.00365399 0.0058741 0.116101 +EDGE3 1378 1427 -2.99644 -11.4855 -5.70567 0.00756108 0.00524484 -0.126171 +EDGE3 1379 1429 -2.36099 0.00410654 -5.83443 0.000207824 -0.00814561 0.00126078 +EDGE3 1378 1429 -3.10072 11.483 -5.93977 6.62133e-05 0.00969372 0.130531 +EDGE3 1379 1428 -3.02497 -11.4814 -5.72523 0.000614617 -0.00226643 -0.123547 +EDGE3 1380 1430 -2.36746 0.0178478 -5.84304 -0.0115887 -0.00126287 -4.07256e-05 +EDGE3 1379 1430 -3.11829 11.4729 -5.94777 -0.00348127 0.00215852 0.128064 +EDGE3 1380 1429 -3.01905 -11.4671 -5.70586 -0.00183774 0.00557964 -0.133634 +EDGE3 1381 1431 -2.35864 0.0129998 -5.81777 -0.00452356 -0.00568206 -0.00183378 +EDGE3 1380 1431 -3.12391 11.4626 -5.92034 0.00734852 -0.00177675 0.128224 +EDGE3 1381 1430 -3.03734 -11.4673 -5.71845 -0.00231555 -0.0016615 -0.122973 +EDGE3 1382 1432 -2.37407 0.00168262 -5.82809 0.00420993 -0.00050782 0.00726334 +EDGE3 1381 1432 -3.13039 11.4738 -5.94169 -0.00455199 0.0111108 0.13029 +EDGE3 1382 1431 -3.02311 -11.4838 -5.71868 0.000444025 0.0120141 -0.127952 +EDGE3 1383 1433 -2.37053 0.0037188 -5.83674 -0.00844058 0.00268044 -0.00447606 +EDGE3 1382 1433 -3.13987 11.4414 -5.93984 -0.00298402 -0.000221844 0.119496 +EDGE3 1383 1432 -3.0369 -11.4544 -5.69757 -0.0211514 0.00142936 -0.110367 +EDGE3 1384 1434 -2.39005 0.00150666 -5.81265 -0.00368792 -0.00474104 -0.00516222 +EDGE3 1383 1434 -3.14785 11.4428 -5.93305 -0.00393889 -0.00192228 0.128601 +EDGE3 1384 1433 -3.03409 -11.4553 -5.70563 -0.00616136 -0.00404152 -0.128225 +EDGE3 1385 1435 -2.36555 0.00160754 -5.80715 -0.0111066 0.00450351 0.0142738 +EDGE3 1384 1435 -3.15086 11.4455 -5.91564 0.00362311 -0.00923984 0.127925 +EDGE3 1385 1434 -3.05245 -11.4523 -5.70076 -0.00171923 0.000193516 -0.118379 +EDGE3 1386 1436 -2.40001 0.00321643 -5.79658 -0.00107261 0.00357173 0.000928172 +EDGE3 1385 1436 -3.15272 11.4203 -5.92296 0.0063208 -0.00755317 0.133455 +EDGE3 1386 1435 -3.06187 -11.417 -5.6928 0.00692614 -0.0114058 -0.119945 +EDGE3 1387 1437 -2.39981 0.00819449 -5.79501 -0.00336273 -0.00789369 0.00111894 +EDGE3 1386 1437 -3.16404 11.4196 -5.92199 0.00356836 -0.00139859 0.134907 +EDGE3 1387 1436 -3.07827 -11.4293 -5.68984 0.00542629 0.0095737 -0.127323 +EDGE3 1388 1438 -2.41213 -0.00886482 -5.78662 -0.00264805 0.0145064 0.000435654 +EDGE3 1387 1438 -3.17555 11.4172 -5.90636 0.00033516 0.00468506 0.124902 +EDGE3 1388 1437 -3.09031 -11.4251 -5.70708 0.00171596 -0.000903737 -0.127224 +EDGE3 1389 1439 -2.39746 -0.0014406 -5.8126 0.00165691 0.00492692 -0.0110674 +EDGE3 1388 1439 -3.16765 11.4084 -5.90675 -7.43948e-05 -0.000506856 0.129847 +EDGE3 1389 1438 -3.09254 -11.419 -5.68381 -0.00320677 0.000966567 -0.121645 +EDGE3 1390 1440 -2.42249 0.0025341 -5.79043 0.000579071 -0.00377649 0.000396273 +EDGE3 1389 1440 -3.18633 11.4148 -5.90238 -0.014347 -0.00414307 0.113243 +EDGE3 1390 1439 -3.10067 -11.417 -5.68664 -0.00540153 0.00300326 -0.132712 +EDGE3 1391 1441 -2.43251 0.0122439 -5.79403 -0.00289125 -0.00921633 0.00156272 +EDGE3 1390 1441 -3.18577 11.4088 -5.88666 -0.00114155 -0.00782858 0.122032 +EDGE3 1391 1440 -3.08695 -11.3977 -5.65903 0.00976536 -0.00545229 -0.125634 +EDGE3 1392 1442 -2.42634 0.00952624 -5.78506 -0.0088021 0.00166646 -0.00231507 +EDGE3 1391 1442 -3.21461 11.3768 -5.92287 0.00359752 0.00349226 0.127898 +EDGE3 1392 1441 -3.09616 -11.3986 -5.68395 0.00342265 -0.00303383 -0.132071 +EDGE3 1393 1443 -2.45456 0.0136242 -5.77217 -0.00379116 0.00148826 0.000706008 +EDGE3 1392 1443 -3.21531 11.3827 -5.90087 0.00080239 -0.00109662 0.126661 +EDGE3 1393 1442 -3.10448 -11.3919 -5.68363 0.000143597 0.00555986 -0.135291 +EDGE3 1394 1444 -2.45528 -0.00705639 -5.78234 0.00171385 -0.00749459 -0.000840034 +EDGE3 1393 1444 -3.21178 11.3696 -5.91792 -0.00179468 0.00340267 0.122346 +EDGE3 1394 1443 -3.0994 -11.3961 -5.68052 -0.000942719 -0.00428198 -0.12221 +EDGE3 1395 1445 -2.45722 -0.0114776 -5.77829 0.00259961 -0.00300421 -0.000257548 +EDGE3 1394 1445 -3.20734 11.3703 -5.89715 -0.000773842 -0.0035928 0.124711 +EDGE3 1395 1444 -3.13386 -11.3866 -5.67225 0.00923595 0.00129069 -0.130052 +EDGE3 1396 1446 -2.46599 -0.0014578 -5.77695 -0.00726054 0.0069381 0.000778885 +EDGE3 1395 1446 -3.23204 11.3576 -5.90448 -0.01009 -0.00241076 0.121992 +EDGE3 1396 1445 -3.12712 -11.3733 -5.65711 -0.00610241 0.00928759 -0.129696 +EDGE3 1397 1447 -2.49691 -0.00492325 -5.77908 0.0033435 -0.00218859 0.00405549 +EDGE3 1396 1447 -3.23753 11.374 -5.89145 -0.00280145 -0.00205007 0.13171 +EDGE3 1397 1446 -3.13259 -11.3718 -5.65528 0.0129821 0.00240126 -0.125561 +EDGE3 1398 1448 -2.4762 0.0227563 -5.76951 -0.000528655 -0.00431008 0.00890635 +EDGE3 1397 1448 -3.23382 11.3515 -5.88887 0.00632209 -0.000331738 0.129136 +EDGE3 1398 1447 -3.14522 -11.3539 -5.66361 -0.00410341 -0.0116064 -0.127732 +EDGE3 1399 1449 -2.49619 -0.0213419 -5.75234 0.00312638 -0.00631455 0.0100218 +EDGE3 1398 1449 -3.25728 11.3494 -5.87952 -0.00185935 0.00560907 0.12142 +EDGE3 1399 1448 -3.14382 -11.3706 -5.65347 0.0101214 0.00119009 -0.127515 +EDGE3 1400 1450 -2.51116 -0.00409776 -5.76849 0.000683116 0.00339789 0.00401137 +EDGE3 1399 1450 -3.25238 11.3509 -5.87727 -0.00275281 0.000352301 0.125025 +EDGE3 1400 1449 -3.15765 -11.3548 -5.65443 0.000321587 -0.00831389 -0.131236 +EDGE3 1401 1451 -2.48521 -0.0124538 -5.76841 0.00755159 -0.00288245 -0.00146646 +EDGE3 1400 1451 -3.26226 11.3275 -5.8775 -0.000775627 -0.00356031 0.123816 +EDGE3 1401 1450 -3.17531 -11.361 -5.64107 -0.00185435 0.00656927 -0.132296 +EDGE3 1402 1452 -2.49589 -0.0157905 -5.76397 0.00337121 -0.000183142 -0.0034783 +EDGE3 1401 1452 -3.27524 11.3311 -5.88984 0.00630465 0.0060838 0.12677 +EDGE3 1402 1451 -3.1635 -11.3563 -5.65303 0.00443324 -0.00331209 -0.124389 +EDGE3 1403 1453 -2.52537 -0.00594871 -5.74249 0.00363703 0.00344805 -0.00272493 +EDGE3 1402 1453 -3.28624 11.3043 -5.87494 0.00472992 -0.00106439 0.123426 +EDGE3 1403 1452 -3.18159 -11.3115 -5.63886 0.00569119 0.00343184 -0.137212 +EDGE3 1404 1454 -2.51607 -0.00603829 -5.73803 0.000950265 0.00515887 0.000452581 +EDGE3 1403 1454 -3.29699 11.3061 -5.86637 0.00579301 -0.00176469 0.118791 +EDGE3 1404 1453 -3.16932 -11.3109 -5.63284 0.00162186 -0.00355046 -0.126428 +EDGE3 1405 1455 -2.5272 0.000656615 -5.76003 -0.00755971 -0.00135987 -0.00952036 +EDGE3 1404 1455 -3.29467 11.306 -5.87011 0.00439459 0.000769998 0.129051 +EDGE3 1405 1454 -3.18934 -11.3022 -5.63825 -0.00529411 -0.000202259 -0.129231 +EDGE3 1406 1456 -2.53427 0.0027544 -5.75022 -0.000228386 0.00267798 0.00635421 +EDGE3 1406 1455 -3.18223 -11.3097 -5.62174 -0.0107863 -0.00271104 -0.111115 +EDGE3 1405 1456 -3.30507 11.301 -5.86355 0.00028346 0.00324735 0.1299 +EDGE3 1407 1457 -2.55426 0.00114953 -5.75388 0.0015796 0.0162836 0.00132451 +EDGE3 1406 1457 -3.31667 11.2858 -5.85098 0.00192668 -0.00961786 0.124355 +EDGE3 1407 1456 -3.20773 -11.286 -5.62414 -0.00281891 -0.00498004 -0.121679 +EDGE3 1408 1458 -2.56755 -0.000119075 -5.73292 -0.00216575 0.00219456 -0.00223093 +EDGE3 1407 1458 -3.31651 11.285 -5.8534 -0.00157609 -0.00300849 0.114345 +EDGE3 1408 1457 -3.22629 -11.2831 -5.62323 0.00155753 -0.000896623 -0.12888 +EDGE3 1409 1459 -2.55754 0.00455343 -5.73625 -0.000365443 0.00585974 -0.00136417 +EDGE3 1408 1459 -3.30821 11.265 -5.84876 -0.00308261 -0.0020447 0.133587 +EDGE3 1409 1458 -3.23096 -11.3032 -5.62304 0.001401 0.00812587 -0.11992 +EDGE3 1410 1460 -2.55584 -0.00337109 -5.72617 -0.00863035 -0.00330919 0.00558037 +EDGE3 1409 1460 -3.33953 11.2748 -5.85779 0.00577023 -0.00205039 0.12213 +EDGE3 1410 1459 -3.23957 -11.2912 -5.61893 -0.012736 0.00257779 -0.113418 +EDGE3 1411 1461 -2.56038 -0.00946869 -5.71988 0.00309232 -0.00157244 0.00415676 +EDGE3 1410 1461 -3.33207 11.2655 -5.85397 0.00629251 -0.000864038 0.122496 +EDGE3 1411 1460 -3.23657 -11.2792 -5.63301 0.00238282 0.00496861 -0.116857 +EDGE3 1412 1462 -2.57269 -0.000405173 -5.73253 -0.00173136 0.00245601 0.00116458 +EDGE3 1411 1462 -3.33594 11.2616 -5.84999 -0.00276663 -0.00163724 0.131309 +EDGE3 1412 1461 -3.2372 -11.281 -5.61913 0.00996514 0.00559401 -0.12721 +EDGE3 1413 1463 -2.57925 -0.00348118 -5.7256 -0.00187753 0.00495906 -0.000748259 +EDGE3 1412 1463 -3.34504 11.2466 -5.83857 0.00495612 -0.00266843 0.130416 +EDGE3 1413 1462 -3.23836 -11.2789 -5.59886 0.00563452 0.0015863 -0.121631 +EDGE3 1414 1464 -2.58499 0.0115179 -5.72675 -0.00261868 0.00428278 -0.00400632 +EDGE3 1413 1464 -3.3377 11.2499 -5.83084 -0.000312908 -0.00167721 0.128462 +EDGE3 1414 1463 -3.23097 -11.2571 -5.63055 0.00387703 0.0117649 -0.131354 +EDGE3 1415 1465 -2.59628 0.0146975 -5.71809 0.00040744 -0.00378831 -0.00256947 +EDGE3 1414 1465 -3.3603 11.2648 -5.82988 -0.00447449 -0.00834244 0.114717 +EDGE3 1415 1464 -3.25872 -11.2485 -5.60703 0.00387018 0.00302139 -0.124716 +EDGE3 1416 1466 -2.60577 0.00305904 -5.70025 0.00327024 -0.0149745 0.00136906 +EDGE3 1415 1466 -3.377 11.2218 -5.84557 0.000177391 0.0019626 0.132708 +EDGE3 1416 1465 -3.24956 -11.2375 -5.59562 0.00863004 -0.00496056 -0.119492 +EDGE3 1417 1467 -2.61484 0.00436946 -5.71676 -0.0032251 -0.00384091 0.000468286 +EDGE3 1416 1467 -3.38518 11.2406 -5.83177 -0.0125711 0.00988213 0.12516 +EDGE3 1417 1466 -3.27125 -11.2397 -5.59684 -0.00602458 -0.00448815 -0.124309 +EDGE3 1418 1468 -2.61528 0.00064688 -5.71579 -0.00418651 -0.000669222 0.00934853 +EDGE3 1417 1468 -3.36899 11.2182 -5.83721 0.00274807 0.00453714 0.127824 +EDGE3 1418 1467 -3.27472 -11.239 -5.59428 0.000329674 -0.00377459 -0.116211 +EDGE3 1419 1469 -2.61641 0.00262265 -5.70194 -0.000836085 0.00739266 -0.00364297 +EDGE3 1418 1469 -3.38638 11.1995 -5.81684 0.00101536 -0.00445328 0.122853 +EDGE3 1419 1468 -3.28568 -11.2077 -5.60671 0.00596664 -0.00482226 -0.130339 +EDGE3 1420 1470 -2.63483 0.00803992 -5.69968 0.00152253 -0.00129564 0.00320869 +EDGE3 1419 1470 -3.40561 11.1935 -5.81737 9.58078e-05 -0.00385567 0.130566 +EDGE3 1420 1469 -3.29584 -11.21 -5.59564 0.000402544 0.00243566 -0.132542 +EDGE3 1421 1471 -2.65597 -0.0029324 -5.70406 -0.00353633 -0.00569193 0.000962036 +EDGE3 1420 1471 -3.3898 11.1946 -5.82207 0.00116754 -0.00260106 0.122787 +EDGE3 1421 1470 -3.31531 -11.1995 -5.58448 0.00240274 0.00696329 -0.122902 +EDGE3 1422 1472 -2.643 0.0072549 -5.68878 -0.00271707 0.0111126 -0.00140855 +EDGE3 1421 1472 -3.40682 11.184 -5.80035 -0.00431184 0.0155264 0.127389 +EDGE3 1422 1471 -3.29914 -11.2087 -5.59908 0.0012269 0.000149205 -0.124698 +EDGE3 1423 1473 -2.64924 0.00647185 -5.69383 0.00373333 0.00339419 0.00455092 +EDGE3 1422 1473 -3.42144 11.1629 -5.81813 -0.00928808 -0.00976673 0.125093 +EDGE3 1423 1472 -3.30902 -11.2048 -5.55832 0.0128302 0.00451174 -0.119337 +EDGE3 1424 1474 -2.65643 -0.0264658 -5.67565 0.00774607 5.80981e-05 0.00209857 +EDGE3 1423 1474 -3.44057 11.1866 -5.81357 0.000114718 0.000223448 0.122423 +EDGE3 1424 1473 -3.31217 -11.1916 -5.54935 0.00334001 0.00426942 -0.130148 +EDGE3 1425 1475 -2.67255 -0.0135457 -5.67253 0.000284268 -0.00237701 0.00230505 +EDGE3 1424 1475 -3.41876 11.1575 -5.79684 -9.50579e-05 -0.0113769 0.133133 +EDGE3 1425 1474 -3.30362 -11.184 -5.5587 -0.00484341 0.00660641 -0.127428 +EDGE3 1426 1476 -2.66609 -0.000342451 -5.68387 0.000940114 0.0042832 -0.00533968 +EDGE3 1425 1476 -3.4402 11.1673 -5.78329 -0.00450174 0.00462107 0.127244 +EDGE3 1426 1475 -3.33259 -11.1611 -5.57106 -0.00216024 -0.00122585 -0.129001 +EDGE3 1427 1477 -2.67874 0.00455244 -5.66822 0.00925505 -0.000864875 -0.000292955 +EDGE3 1426 1477 -3.45226 11.1475 -5.81133 0.00156882 0.00404512 0.126136 +EDGE3 1427 1476 -3.34585 -11.152 -5.53681 -0.00562672 -0.00180824 -0.123817 +EDGE3 1428 1478 -2.69224 0.00981948 -5.68193 -0.00135094 0.00558074 0.00605272 +EDGE3 1427 1478 -3.44663 11.1443 -5.78712 -0.0095858 -0.00171284 0.123748 +EDGE3 1428 1477 -3.33179 -11.1586 -5.54466 -0.00229092 -0.00590133 -0.134915 +EDGE3 1429 1479 -2.70902 -0.0150968 -5.67795 -0.00279965 -0.000729584 0.00586528 +EDGE3 1428 1479 -3.44389 11.1491 -5.79837 -0.00571493 0.00120026 0.134068 +EDGE3 1429 1478 -3.34737 -11.1478 -5.57062 0.00582232 0.00781458 -0.132797 +EDGE3 1430 1480 -2.71352 -0.00604255 -5.66348 -0.00250387 0.00197402 -0.00419338 +EDGE3 1429 1480 -3.45749 11.1357 -5.7818 0.00095691 -0.00334008 0.12926 +EDGE3 1430 1479 -3.34437 -11.1513 -5.57257 0.000495014 -0.00155308 -0.116142 +EDGE3 1431 1481 -2.73402 -0.00375305 -5.66605 -0.000489123 0.00332675 0.00681011 +EDGE3 1430 1481 -3.46638 11.1252 -5.77958 0.00274031 0.00562718 0.13029 +EDGE3 1431 1480 -3.36927 -11.1427 -5.57105 -0.00565752 -0.000215283 -0.131286 +EDGE3 1432 1482 -2.73165 -0.0158827 -5.66152 -0.000439031 -0.00383595 -0.000662837 +EDGE3 1431 1482 -3.49306 11.1245 -5.77443 -0.00465623 0.0060127 0.121327 +EDGE3 1432 1481 -3.38257 -11.1356 -5.53411 -0.00558735 -0.00366963 -0.123547 +EDGE3 1433 1483 -2.73212 -0.0117035 -5.65875 -0.0054219 -0.000891107 -0.00347713 +EDGE3 1432 1483 -3.47603 11.1433 -5.7842 -0.00410611 0.00527587 0.126228 +EDGE3 1433 1482 -3.36802 -11.1011 -5.54939 -0.00341541 0.00638435 -0.131694 +EDGE3 1434 1484 -2.73268 -0.00778635 -5.65608 -0.00213185 -0.00692638 0.00236521 +EDGE3 1433 1484 -3.47858 11.1053 -5.77255 -0.00494056 0.00296691 0.128853 +EDGE3 1434 1483 -3.38176 -11.1006 -5.54744 0.00171519 -0.000382897 -0.131834 +EDGE3 1435 1485 -2.74662 -0.0125737 -5.65512 0.000832974 0.00897526 -0.00101962 +EDGE3 1434 1485 -3.49372 11.1034 -5.76739 0.00449267 0.00117118 0.125398 +EDGE3 1435 1484 -3.39029 -11.1008 -5.51589 -0.000963355 -0.0034631 -0.127519 +EDGE3 1435 1486 -3.50174 11.1009 -5.76051 0.0077356 -0.00482213 0.129603 +EDGE3 1436 1486 -2.75181 0.0132258 -5.66021 0.00230421 -0.0033201 0.00223483 +EDGE3 1437 1487 -2.75922 -0.00616133 -5.65511 0.00122771 0.000237489 0.00100046 +EDGE3 1436 1485 -3.38979 -11.1051 -5.54623 -0.00295137 -0.00659435 -0.125624 +EDGE3 1436 1487 -3.4935 11.1024 -5.7586 -0.0017107 0.0059031 0.117024 +EDGE3 1437 1486 -3.4083 -11.0643 -5.52466 -0.00663832 0.00773309 -0.12602 +EDGE3 1438 1488 -2.7734 0.00163961 -5.64318 0.00317729 -0.00171556 -0.00106887 +EDGE3 1437 1488 -3.51269 11.0715 -5.74819 0.00948592 0.00469768 0.125656 +EDGE3 1438 1487 -3.4016 -11.0842 -5.52362 0.00328703 0.000435361 -0.123586 +EDGE3 1439 1489 -2.76457 0.00616964 -5.6639 -0.00453745 -0.0053623 -0.00203013 +EDGE3 1438 1489 -3.54234 11.0672 -5.72874 0.00180431 -0.00207949 0.131056 +EDGE3 1439 1488 -3.4208 -11.0871 -5.53203 -0.000951846 0.00120236 -0.133541 +EDGE3 1440 1490 -2.76807 -0.00856747 -5.65457 -0.00206982 -0.00445226 0.0033067 +EDGE3 1439 1490 -3.53768 11.048 -5.74592 0.0140956 -0.00093805 0.128043 +EDGE3 1440 1489 -3.42008 -11.0542 -5.51565 0.002396 0.00229822 -0.120119 +EDGE3 1441 1491 -2.78497 -0.00185082 -5.659 0.00139777 0.00210812 -0.00372818 +EDGE3 1440 1491 -3.52873 11.0463 -5.75181 0.00794401 -0.00219174 0.134015 +EDGE3 1441 1490 -3.41962 -11.0505 -5.51925 0.0087805 0.00107607 -0.119571 +EDGE3 1442 1492 -2.79461 0.00959898 -5.64149 0.00172405 -0.00672778 -0.00107178 +EDGE3 1441 1492 -3.54522 11.0542 -5.73926 0.00240628 0.00169831 0.118858 +EDGE3 1442 1491 -3.42798 -11.0557 -5.51912 -0.00106597 -0.000380084 -0.131011 +EDGE3 1443 1493 -2.81422 0.00253006 -5.61637 0.00166022 -0.00423617 -0.00798885 +EDGE3 1442 1493 -3.54135 11.044 -5.72066 0.00176987 0.00507762 0.121897 +EDGE3 1444 1494 -2.81744 -0.00616017 -5.60465 -0.00494247 0.00134229 0.00269949 +EDGE3 1443 1492 -3.43367 -11.0432 -5.50641 0.00329887 -0.00621278 -0.123795 +EDGE3 1443 1494 -3.57552 11.0255 -5.72819 -0.000124976 -0.00200782 0.136625 +EDGE3 1444 1493 -3.45151 -11.0428 -5.50318 0.00718203 -0.00167067 -0.13043 +EDGE3 1445 1495 -2.8002 -0.00841318 -5.62115 0.00414226 0.000774577 -0.00274227 +EDGE3 1444 1495 -3.56764 11.0192 -5.71247 0.000896775 0.00106848 0.127066 +EDGE3 1445 1494 -3.44359 -11.0292 -5.50068 -0.0012264 -0.00136155 -0.116433 +EDGE3 1446 1496 -2.82194 -0.00937098 -5.62457 6.04879e-05 -0.00852213 2.37342e-05 +EDGE3 1445 1496 -3.56763 11.0152 -5.73184 0.00319088 0.00484179 0.12335 +EDGE3 1446 1495 -3.45931 -11.0263 -5.4758 0.00206778 -0.00337639 -0.127415 +EDGE3 1447 1497 -2.82962 -0.00360923 -5.61619 0.00203264 0.000865922 0.00578439 +EDGE3 1446 1497 -3.57665 11.0074 -5.72461 0.00776701 0.00795247 0.121304 +EDGE3 1447 1496 -3.46728 -11.0003 -5.48518 0.000458119 -0.00404805 -0.126236 +EDGE3 1448 1498 -2.81547 -0.00714143 -5.59524 -0.00306901 -0.00464821 -0.0108167 +EDGE3 1447 1498 -3.58647 10.9847 -5.70529 0.000805165 -0.00268278 0.136274 +EDGE3 1448 1497 -3.46438 -10.9907 -5.51478 0.00180977 -0.0050706 -0.122992 +EDGE3 1449 1499 -2.84594 0.00625667 -5.60971 -0.00836935 -0.00440722 -0.000908433 +EDGE3 1448 1499 -3.60617 11.0054 -5.71724 0.00427682 -0.00823383 0.123736 +EDGE3 1449 1498 -3.47123 -11.0034 -5.48684 0.00344935 0.00782358 -0.130211 +EDGE3 1449 1500 -3.59072 10.9917 -5.68912 0.00033721 0.00673651 0.124838 +EDGE3 1450 1500 -2.84929 0.00432901 -5.60941 0.00324497 -0.00678114 0.010171 +EDGE3 1451 1501 -2.85478 0.00526851 -5.60465 -0.00913822 0.000656339 0.000893154 +EDGE3 1450 1499 -3.48765 -10.9892 -5.46984 0.00302994 -0.00840451 -0.125254 +EDGE3 1450 1501 -3.59433 10.9679 -5.70994 0.00235761 0.00197233 0.12594 +EDGE3 1451 1500 -3.5093 -10.9797 -5.49938 -0.00427316 -0.00684061 -0.1357 +EDGE3 1451 1502 -3.61519 10.9758 -5.71783 -0.016007 -0.00736859 0.119428 +EDGE3 1452 1502 -2.87178 0.0145206 -5.57602 0.00589478 0.00431427 0.0102364 +EDGE3 1453 1503 -2.88521 0.00546249 -5.58936 3.29167e-06 -0.00305485 0.00239846 +EDGE3 1452 1501 -3.48981 -10.9751 -5.46573 -0.00637206 -0.00426297 -0.126864 +EDGE3 1452 1503 -3.60374 10.9607 -5.70362 0.00603507 -0.00278536 0.130854 +EDGE3 1453 1502 -3.49995 -10.9667 -5.47951 0.0037669 0.00584575 -0.127672 +EDGE3 1454 1504 -2.89432 0.00510481 -5.5822 0.00281199 0.00353803 0.000103062 +EDGE3 1453 1504 -3.63757 10.9609 -5.71238 0.0105568 0.00414117 0.115704 +EDGE3 1454 1503 -3.50994 -10.9498 -5.46654 0.00304232 -0.00506095 -0.12514 +EDGE3 1455 1505 -2.89561 0.000295331 -5.57934 0.00217491 -0.00137602 -0.00258596 +EDGE3 1454 1505 -3.63803 10.9565 -5.69966 9.62191e-06 -0.00162973 0.119854 +EDGE3 1455 1504 -3.52225 -10.9405 -5.46631 -0.00275404 0.00784867 -0.136293 +EDGE3 1456 1506 -2.88455 -0.00369868 -5.57219 -0.00444815 0.000189524 -0.00422039 +EDGE3 1455 1506 -3.6288 10.9363 -5.7012 -0.00316675 0.0142675 0.1298 +EDGE3 1456 1505 -3.51573 -10.93 -5.46575 -0.0011697 -0.00365719 -0.122632 +EDGE3 1457 1507 -2.90255 0.00619833 -5.56554 -0.000880792 -0.00848173 -0.0118524 +EDGE3 1456 1507 -3.64908 10.922 -5.67585 0.00262252 0.00469454 0.132788 +EDGE3 1458 1508 -2.89523 0.00904123 -5.556 0.00394008 -0.00158379 0.00513994 +EDGE3 1457 1506 -3.52458 -10.9326 -5.46812 -0.000527025 0.00388456 -0.128714 +EDGE3 1458 1507 -3.54105 -10.9401 -5.46299 0.00652906 0.0118155 -0.12217 +EDGE3 1457 1508 -3.65664 10.944 -5.66513 0.00197157 -0.00246858 0.120182 +EDGE3 1459 1509 -2.91027 -0.01045 -5.57436 -0.00465881 0.00844032 0.000438192 +EDGE3 1458 1509 -3.66337 10.9081 -5.68207 -0.0016352 0.00697288 0.12255 +EDGE3 1459 1508 -3.54233 -10.924 -5.45437 -0.00245967 0.00368546 -0.126559 +EDGE3 1460 1510 -2.91531 -0.00605302 -5.55489 -0.000684003 0.0078624 0.00217898 +EDGE3 1459 1510 -3.65852 10.9132 -5.69033 0.0110744 -0.00176858 0.127933 +EDGE3 1460 1509 -3.55395 -10.9166 -5.45894 -0.00238068 -0.00276497 -0.130673 +EDGE3 1461 1511 -2.92917 -0.000859272 -5.57261 0.00141517 0.00221116 -0.0022714 +EDGE3 1460 1511 -3.67507 10.8975 -5.66487 -0.0124876 -0.00283578 0.117722 +EDGE3 1461 1510 -3.54481 -10.9235 -5.43611 0.000320767 0.00417354 -0.122504 +EDGE3 1462 1512 -2.93551 -0.00965368 -5.54005 0.00244065 0.00289408 0.00219067 +EDGE3 1461 1512 -3.68294 10.8881 -5.66311 -0.00551703 0.00984827 0.122126 +EDGE3 1462 1511 -3.54408 -10.8965 -5.45967 -0.00517811 -0.00124878 -0.133802 +EDGE3 1463 1513 -2.9701 -0.0111825 -5.54872 -0.00577691 0.00294611 -0.000603616 +EDGE3 1462 1513 -3.68899 10.8723 -5.65391 -0.00264416 0.00509568 0.124021 +EDGE3 1463 1512 -3.57521 -10.8989 -5.43856 -0.0036946 -0.00645828 -0.124682 +EDGE3 1464 1514 -2.93285 -0.0156707 -5.53287 0.000106833 0.00784522 -0.00239737 +EDGE3 1463 1514 -3.68257 10.8733 -5.6603 0.000942069 0.00409301 0.126684 +EDGE3 1464 1513 -3.58585 -10.89 -5.43994 0.00547557 0.00306459 -0.12767 +EDGE3 1465 1515 -2.95984 0.0225991 -5.54809 0.00340336 -0.00189502 0.00481711 +EDGE3 1464 1515 -3.68836 10.8556 -5.6462 -0.00350617 -0.00440824 0.125403 +EDGE3 1465 1514 -3.58055 -10.8684 -5.45471 0.00899103 -0.00562263 -0.126365 +EDGE3 1466 1516 -2.96027 0.0188499 -5.54606 -0.00724769 -0.00326112 -0.00679317 +EDGE3 1465 1516 -3.6955 10.8688 -5.65608 0.00638966 -0.00662141 0.114734 +EDGE3 1466 1515 -3.5816 -10.8584 -5.42154 0.00259785 0.0140728 -0.13602 +EDGE3 1467 1517 -2.96692 -0.0113294 -5.55755 -0.00740837 -0.00760572 0.0067711 +EDGE3 1466 1517 -3.7045 10.8593 -5.62935 -0.000253434 -0.00360656 0.124688 +EDGE3 1467 1516 -3.588 -10.86 -5.42198 -0.00270217 -0.00230404 -0.128783 +EDGE3 1468 1518 -2.98061 -0.00703382 -5.54136 0.00120064 0.00516916 -0.00630347 +EDGE3 1467 1518 -3.72914 10.8381 -5.66386 -0.00435416 -0.00549984 0.116553 +EDGE3 1468 1517 -3.60986 -10.8563 -5.4329 0.00153298 -0.00134019 -0.139682 +EDGE3 1469 1519 -2.98462 0.00169071 -5.52377 0.00180341 -0.00180217 -0.00619437 +EDGE3 1468 1519 -3.71944 10.8399 -5.64982 0.00295103 0.00640798 0.119332 +EDGE3 1469 1518 -3.60279 -10.8371 -5.42862 0.000663197 0.00411912 -0.118499 +EDGE3 1470 1520 -2.98589 -0.0057942 -5.53048 -0.000127546 0.000472713 0.00458818 +EDGE3 1469 1520 -3.72746 10.8344 -5.64199 0.00159458 -0.0054954 0.132259 +EDGE3 1470 1519 -3.60216 -10.8327 -5.42149 -0.00190689 -0.00197094 -0.120018 +EDGE3 1471 1521 -3.00065 -0.00916784 -5.52245 -0.00258212 -0.00620428 0.00358675 +EDGE3 1470 1521 -3.74262 10.8236 -5.62556 0.00454177 -0.00636466 0.119304 +EDGE3 1471 1520 -3.61012 -10.8477 -5.42404 0.000532619 0.00583992 -0.131708 +EDGE3 1472 1522 -3.00501 -0.00172423 -5.52395 0.00219995 0.000682781 0.00681885 +EDGE3 1471 1522 -3.7316 10.8056 -5.63615 -0.0107112 -0.00357642 0.129531 +EDGE3 1472 1521 -3.62319 -10.8013 -5.40108 -0.00471786 0.00460305 -0.114293 +EDGE3 1473 1523 -3.00714 0.00668822 -5.51189 0.00538637 0.00200124 0.00882843 +EDGE3 1472 1523 -3.75965 10.792 -5.63491 -0.0131487 -0.00418266 0.123394 +EDGE3 1473 1522 -3.62207 -10.8039 -5.40337 -0.00352914 -0.00668286 -0.125057 +EDGE3 1474 1524 -3.01441 0.00118454 -5.50765 -0.00391291 0.00708384 -0.00752559 +EDGE3 1473 1524 -3.74619 10.7842 -5.62121 0.000430772 -0.00566346 0.125665 +EDGE3 1474 1523 -3.64353 -10.8184 -5.40022 0.00347607 0.00724062 -0.122146 +EDGE3 1475 1525 -3.02775 -0.0273248 -5.51721 -0.000532707 0.00320232 0.00200942 +EDGE3 1474 1525 -3.78615 10.7815 -5.62814 -7.51954e-05 0.001654 0.129379 +EDGE3 1475 1524 -3.63131 -10.7982 -5.39316 0.00424659 0.00278551 -0.134089 +EDGE3 1476 1526 -3.03409 0.0122034 -5.50328 0.00307039 -0.000561299 -0.000332066 +EDGE3 1475 1526 -3.76499 10.7831 -5.60423 0.000724418 -0.00737935 0.131147 +EDGE3 1476 1525 -3.65988 -10.7976 -5.39174 0.00131436 -0.000595005 -0.12906 +EDGE3 1477 1527 -3.03126 0.00412424 -5.50563 0.00787423 -7.92677e-05 0.00511334 +EDGE3 1476 1527 -3.76829 10.7819 -5.59814 -0.00428279 -0.00290308 0.125749 +EDGE3 1477 1526 -3.65599 -10.7745 -5.38502 -0.00625614 0.00175338 -0.123718 +EDGE3 1478 1528 -3.03583 -0.00459215 -5.47702 -0.0017379 -0.00272211 0.00353867 +EDGE3 1477 1528 -3.78962 10.762 -5.60043 -0.00142081 0.00893417 0.123663 +EDGE3 1478 1527 -3.67535 -10.7894 -5.37885 -0.0066576 -0.000595987 -0.124287 +EDGE3 1479 1529 -3.05567 -0.0189481 -5.47766 -0.00373911 0.00244372 0.00283435 +EDGE3 1478 1529 -3.79968 10.7572 -5.59174 0.00169201 -3.8441e-05 0.119872 +EDGE3 1479 1528 -3.66876 -10.7739 -5.36767 -0.00349811 -0.006589 -0.114257 +EDGE3 1480 1530 -3.06667 8.79437e-06 -5.48258 -0.00856264 0.00577917 -0.0075877 +EDGE3 1479 1530 -3.79567 10.7385 -5.57856 0.000426648 -0.00560061 0.127098 +EDGE3 1480 1529 -3.68228 -10.7699 -5.38776 -0.00268422 -0.00231433 -0.12509 +EDGE3 1481 1531 -3.06275 -0.00848308 -5.48009 -0.000360959 0.00659912 -0.000675461 +EDGE3 1480 1531 -3.80012 10.7285 -5.58297 0.000130585 -0.000298726 0.128798 +EDGE3 1481 1530 -3.67558 -10.7439 -5.38089 -0.00293304 -0.00051304 -0.129615 +EDGE3 1482 1532 -3.07036 -0.0105173 -5.47812 0.013077 -0.001994 0.00205078 +EDGE3 1481 1532 -3.80137 10.7354 -5.59027 0.0021468 -0.00477332 0.121292 +EDGE3 1482 1531 -3.70114 -10.7316 -5.3779 0.00686032 0.00657484 -0.123084 +EDGE3 1483 1533 -3.07438 0.0164715 -5.46159 0.003481 0.0031752 0.00518108 +EDGE3 1482 1533 -3.82784 10.723 -5.58552 -0.00844719 -0.00145556 0.121959 +EDGE3 1483 1532 -3.68687 -10.7362 -5.36899 0.00203284 -0.0061121 -0.126473 +EDGE3 1484 1534 -3.10274 -0.0132774 -5.47752 -0.00105101 -0.00643101 -0.000226166 +EDGE3 1483 1534 -3.82425 10.7215 -5.57981 -0.00337563 7.91389e-05 0.123812 +EDGE3 1484 1533 -3.69394 -10.7244 -5.34299 0.00207979 -0.00450844 -0.126827 +EDGE3 1485 1535 -3.11388 -0.00336538 -5.46316 -0.00104981 0.00065507 -0.00113896 +EDGE3 1484 1535 -3.83845 10.7012 -5.58572 -0.0037816 0.00420927 0.124266 +EDGE3 1485 1534 -3.70098 -10.7256 -5.34312 -0.00180757 -0.00834078 -0.119924 +EDGE3 1486 1536 -3.08745 0.00482868 -5.47773 0.00338158 -0.00126772 -2.51139e-05 +EDGE3 1485 1536 -3.82628 10.6762 -5.57409 0.00306607 -0.00446962 0.123596 +EDGE3 1486 1535 -3.69204 -10.706 -5.35597 0.00307867 0.00352418 -0.125415 +EDGE3 1487 1537 -3.10054 0.000561335 -5.45347 0.00257943 0.0038149 0.00825911 +EDGE3 1486 1537 -3.84232 10.7032 -5.57094 -0.00471528 0.0040507 0.123224 +EDGE3 1487 1536 -3.70658 -10.7088 -5.33415 -0.00283842 -0.00646614 -0.124472 +EDGE3 1488 1538 -3.09851 0.00340708 -5.46607 0.00816715 0.00921622 -0.00577539 +EDGE3 1487 1538 -3.84406 10.6769 -5.57439 -0.00489823 0.00516677 0.126995 +EDGE3 1488 1537 -3.7206 -10.6888 -5.33847 -0.00607787 -0.0061083 -0.123191 +EDGE3 1489 1539 -3.13626 -0.00272486 -5.45168 -0.00251326 0.00406789 -0.0107638 +EDGE3 1488 1539 -3.85007 10.66 -5.54827 0.00178338 -0.0125929 0.120362 +EDGE3 1489 1538 -3.73984 -10.6793 -5.3606 0.0031659 0.0043871 -0.129426 +EDGE3 1490 1540 -3.14045 0.00101574 -5.44341 0.00296604 0.0103256 -0.00337717 +EDGE3 1489 1540 -3.87369 10.6458 -5.55326 0.00662208 0.00334753 0.122564 +EDGE3 1490 1539 -3.74941 -10.6726 -5.34081 -0.000129991 -0.00385127 -0.128564 +EDGE3 1491 1541 -3.13566 0.00162465 -5.42202 0.0104003 0.00713443 -0.00156484 +EDGE3 1490 1541 -3.87287 10.6466 -5.55299 -0.00191306 -0.0108899 0.128108 +EDGE3 1491 1540 -3.74216 -10.6639 -5.33155 -0.00909836 0.00126419 -0.134022 +EDGE3 1492 1542 -3.15478 0.00208178 -5.4321 -0.00635823 -0.00147532 -0.00105229 +EDGE3 1491 1542 -3.86688 10.6481 -5.55581 -0.0085326 -0.00435925 0.133928 +EDGE3 1492 1541 -3.76518 -10.6747 -5.34244 0.00139985 -0.00585942 -0.133225 +EDGE3 1493 1543 -3.16213 0.00801121 -5.45132 0.000876086 0.00342818 -0.000912451 +EDGE3 1492 1543 -3.87894 10.6372 -5.53707 -0.004727 -0.0035524 0.117083 +EDGE3 1493 1542 -3.74297 -10.6434 -5.29949 -0.00348423 -0.00603978 -0.124046 +EDGE3 1494 1544 -3.1545 0.00194999 -5.42556 0.00834739 0.00829807 -0.00109712 +EDGE3 1493 1544 -3.86892 10.6299 -5.54505 0.00300143 -0.00359816 0.124854 +EDGE3 1494 1543 -3.75685 -10.649 -5.32532 0.00412232 -0.00736267 -0.115544 +EDGE3 1495 1545 -3.18206 -0.00384032 -5.42175 0.00285095 -0.00555932 0.00153945 +EDGE3 1494 1545 -3.89642 10.608 -5.53748 -0.000874186 0.00734301 0.120679 +EDGE3 1495 1544 -3.7704 -10.6357 -5.31094 0.0100734 -0.00308193 -0.131576 +EDGE3 1496 1546 -3.15961 0.00332659 -5.42269 0.00950074 0.00475737 -0.00649217 +EDGE3 1495 1546 -3.90062 10.614 -5.52938 0.00241018 -0.00951835 0.129445 +EDGE3 1496 1545 -3.77123 -10.6207 -5.31937 -0.00122865 0.0100908 -0.125902 +EDGE3 1497 1547 -3.19572 -0.00193143 -5.43272 0.00172976 0.00297702 0.00467913 +EDGE3 1496 1547 -3.9164 10.6088 -5.51279 0.000668297 -0.00540515 0.122614 +EDGE3 1497 1546 -3.78909 -10.5933 -5.32244 0.00242506 0.000919078 -0.127924 +EDGE3 1498 1548 -3.19779 -0.000825006 -5.41625 0.00184103 0.00507089 0.00458658 +EDGE3 1497 1548 -3.91304 10.6165 -5.5267 -0.00639719 -0.00581609 0.121555 +EDGE3 1498 1547 -3.78957 -10.6159 -5.29914 -0.0038781 -0.000582857 -0.128599 +EDGE3 1499 1549 -3.1995 0.00760044 -5.40156 -0.0043111 -0.00307495 0.00101126 +EDGE3 1498 1549 -3.91159 10.5694 -5.51309 -0.00571882 -0.00383373 0.120998 +EDGE3 1499 1548 -3.77741 -10.5997 -5.30878 -0.000661951 -0.00256837 -0.118435 +EDGE3 1500 1550 -3.20003 0.00429252 -5.41792 -0.00327761 0.00269017 0.00058342 +EDGE3 1499 1550 -3.91732 10.5733 -5.52328 0.00153488 0.00706453 0.122429 +EDGE3 1500 1549 -3.79008 -10.5944 -5.27608 -0.000483226 -0.0013095 -0.125347 +EDGE3 1501 1551 -3.2091 0.00564998 -5.40722 -0.00228055 -0.0030906 -0.000604251 +EDGE3 1500 1551 -3.90529 10.5908 -5.52308 -0.00613781 -5.36968e-05 0.122637 +EDGE3 1501 1550 -3.80115 -10.5768 -5.28592 0.00114351 0.00396865 -0.135899 +EDGE3 1502 1552 -3.20046 -0.0219335 -5.40239 0.00774445 0.00823378 -0.00661193 +EDGE3 1501 1552 -3.951 10.5634 -5.49821 0.0106181 -0.00256298 0.135589 +EDGE3 1502 1551 -3.80726 -10.5612 -5.30774 -0.00657967 -0.000224771 -0.121063 +EDGE3 1503 1553 -3.19643 0.00158948 -5.40445 0.00568389 -0.0143987 0.00197334 +EDGE3 1502 1553 -3.96178 10.5549 -5.4952 0.00242294 -0.00539163 0.130389 +EDGE3 1503 1552 -3.83992 -10.5525 -5.27223 0.00418086 0.00152073 -0.124764 +EDGE3 1504 1554 -3.23944 -0.0018978 -5.37631 5.94986e-05 -0.00682973 0.00240542 +EDGE3 1503 1554 -3.95415 10.5671 -5.48937 -0.00299751 -0.0049351 0.121694 +EDGE3 1504 1553 -3.821 -10.5294 -5.28682 -0.00115522 -0.00731157 -0.134288 +EDGE3 1505 1555 -3.23182 -0.00189645 -5.38538 0.00543846 0.000528976 -0.00666967 +EDGE3 1504 1555 -3.93934 10.5519 -5.48203 0.00361343 -0.0010198 0.127928 +EDGE3 1505 1554 -3.83168 -10.5541 -5.27583 -0.00467605 -0.00468801 -0.125255 +EDGE3 1506 1556 -3.23825 0.0343305 -5.38676 0.00296366 -0.00622642 -0.00371505 +EDGE3 1505 1556 -3.969 10.53 -5.49475 -0.00320258 0.00404776 0.13166 +EDGE3 1506 1555 -3.8352 -10.5582 -5.27975 0.00121159 -0.00166528 -0.126317 +EDGE3 1507 1557 -3.23465 -0.00741475 -5.38344 -0.00368374 -0.00143609 0.00286647 +EDGE3 1506 1557 -3.96864 10.5091 -5.49332 0.000359902 0.000817475 0.130523 +EDGE3 1507 1556 -3.84739 -10.536 -5.29048 -0.00804361 -0.00564885 -0.128769 +EDGE3 1508 1558 -3.25931 -0.0247945 -5.37252 0.00433135 -0.00100744 -0.00692064 +EDGE3 1507 1558 -3.94798 10.5052 -5.49097 -0.00664954 0.00422324 0.124761 +EDGE3 1508 1557 -3.83817 -10.5254 -5.27632 0.00428227 0.00367908 -0.124919 +EDGE3 1509 1559 -3.2494 -0.00975667 -5.3628 0.00454096 -0.00011157 0.00270291 +EDGE3 1508 1559 -3.99024 10.5085 -5.48011 -0.0106174 0.00134683 0.130006 +EDGE3 1509 1558 -3.84855 -10.5117 -5.25392 0.0010881 -0.00497193 -0.130647 +EDGE3 1510 1560 -3.26753 -0.00808517 -5.38833 -0.00848883 0.00126572 -0.00308428 +EDGE3 1509 1560 -3.97764 10.4867 -5.47331 -0.00105223 -0.00336771 0.123968 +EDGE3 1510 1559 -3.86312 -10.5181 -5.2516 -0.00105956 -0.0046268 -0.130675 +EDGE3 1511 1561 -3.25786 -0.000940883 -5.36589 0.00431132 -0.00547144 -0.00137101 +EDGE3 1510 1561 -4.01384 10.491 -5.46981 0.000171579 0.00438849 0.126389 +EDGE3 1511 1560 -3.88003 -10.5089 -5.23909 0.00466159 0.00255325 -0.125588 +EDGE3 1512 1562 -3.28222 -0.0204673 -5.35278 -0.00299863 0.00362087 -0.00101814 +EDGE3 1511 1562 -3.99471 10.4852 -5.4774 0.00386082 0.00536992 0.132426 +EDGE3 1512 1561 -3.86608 -10.4845 -5.26279 0.0047337 -0.000773671 -0.125909 +EDGE3 1513 1563 -3.27026 -0.0026923 -5.35607 -0.00319301 -0.00176075 -0.000308565 +EDGE3 1512 1563 -4.00632 10.4763 -5.4561 -0.00422499 -0.00312333 0.125186 +EDGE3 1513 1562 -3.87692 -10.4704 -5.2566 0.00196048 0.0021866 -0.124733 +EDGE3 1514 1564 -3.30168 -0.00835049 -5.34879 0.00111138 -0.00171428 0.00328747 +EDGE3 1513 1564 -4.00753 10.4519 -5.45803 0.00651049 0.00165912 0.125984 +EDGE3 1514 1563 -3.87958 -10.4748 -5.24987 -0.00225894 -0.0034708 -0.117191 +EDGE3 1515 1565 -3.30057 -0.00072943 -5.33732 -0.00257266 0.00573787 -0.00312474 +EDGE3 1514 1565 -4.00234 10.454 -5.46736 0.00100423 4.83297e-05 0.124697 +EDGE3 1515 1564 -3.8883 -10.4588 -5.23217 -0.000575764 0.000677949 -0.12109 +EDGE3 1516 1566 -3.31959 0.00459452 -5.33635 -0.00114615 -0.00777926 0.00440258 +EDGE3 1515 1566 -4.01157 10.4526 -5.42714 -0.0115759 -0.00698753 0.133508 +EDGE3 1516 1565 -3.87932 -10.4473 -5.23692 0.00861464 0.00615491 -0.125513 +EDGE3 1517 1567 -3.30466 -0.0106797 -5.34658 -0.00926816 -0.000154185 0.000896683 +EDGE3 1516 1567 -4.02671 10.4381 -5.47811 -0.00930973 -0.00524926 0.122444 +EDGE3 1517 1566 -3.91082 -10.4548 -5.23006 -0.000327621 -0.00198653 -0.1228 +EDGE3 1518 1568 -3.3154 0.00791378 -5.31576 0.00180786 0.00359704 0.00333225 +EDGE3 1517 1568 -4.02008 10.4124 -5.44747 0.000922741 0.005652 0.122847 +EDGE3 1518 1567 -3.89589 -10.4262 -5.24084 -0.00926229 0.00151465 -0.12692 +EDGE3 1519 1569 -3.31339 0.0142994 -5.32367 0.00295351 0.00503876 -0.00117254 +EDGE3 1518 1569 -4.05346 10.4008 -5.4496 0.00253758 0.0019385 0.124933 +EDGE3 1519 1568 -3.92878 -10.4328 -5.23542 0.00283254 -0.00734652 -0.125524 +EDGE3 1520 1570 -3.33207 0.00812849 -5.32024 0.00141092 0.00178208 -0.00226248 +EDGE3 1519 1570 -4.05529 10.4173 -5.42835 0.0169291 0.000284861 0.131213 +EDGE3 1520 1569 -3.91927 -10.4196 -5.23089 -0.00244167 0.00265959 -0.123931 +EDGE3 1521 1571 -3.33381 0.00607201 -5.34716 0.000992175 0.00446423 0.00079649 +EDGE3 1520 1571 -4.05312 10.3943 -5.42169 -0.00762808 -0.00185017 0.121833 +EDGE3 1521 1570 -3.93911 -10.4103 -5.23279 -0.000883845 -0.00109148 -0.130091 +EDGE3 1522 1572 -3.34813 -0.00496087 -5.31655 0.00263644 -0.00844799 -0.00321555 +EDGE3 1522 1571 -3.94956 -10.4135 -5.22066 0.00781228 0.000502291 -0.120671 +EDGE3 1521 1572 -4.03529 10.3919 -5.42521 -0.00235565 0.00926545 0.12185 +EDGE3 1522 1573 -4.06632 10.3813 -5.42938 0.00106562 -0.00584674 0.128018 +EDGE3 1523 1573 -3.37524 0.00168532 -5.30621 0.00540003 -0.0060005 0.0011052 +EDGE3 1524 1574 -3.37062 -0.0180191 -5.29668 -0.00309857 0.00670476 -0.00599861 +EDGE3 1523 1572 -3.93244 -10.3838 -5.20156 -0.00297814 -0.00394817 -0.119594 +EDGE3 1523 1574 -4.06929 10.3626 -5.41264 0.000795546 -0.00200867 0.127452 +EDGE3 1524 1573 -3.92746 -10.3788 -5.19877 -0.00269868 0.00126156 -0.12349 +EDGE3 1525 1575 -3.36435 -0.011523 -5.28915 0.000492615 -0.00163708 0.0037709 +EDGE3 1524 1575 -4.09401 10.3657 -5.41284 -0.00186757 -0.00285385 0.133215 +EDGE3 1525 1574 -3.93863 -10.3671 -5.19265 -0.00160095 -0.00220529 -0.130084 +EDGE3 1526 1576 -3.35946 -0.00804949 -5.29724 -0.006209 -0.000348838 0.00399435 +EDGE3 1525 1576 -4.09968 10.3552 -5.41311 -0.00382921 0.00254848 0.121702 +EDGE3 1526 1575 -3.94701 -10.3677 -5.19418 0.00333988 -0.000258509 -0.127703 +EDGE3 1527 1577 -3.37099 0.00729784 -5.29153 0.00722158 -0.000381864 0.000166732 +EDGE3 1526 1577 -4.0669 10.3361 -5.41023 0.00264051 0.00455866 0.122765 +EDGE3 1527 1576 -3.97422 -10.3482 -5.20087 0.00428279 -0.00165521 -0.122447 +EDGE3 1528 1578 -3.38379 -0.00324931 -5.28868 -0.0069051 -0.00203343 -0.0100777 +EDGE3 1527 1578 -4.09424 10.3462 -5.3937 0.0139202 0.00603531 0.123594 +EDGE3 1528 1577 -3.94969 -10.3405 -5.19277 -0.00959584 0.00453354 -0.125034 +EDGE3 1529 1579 -3.41054 -0.0112281 -5.30113 0.00384691 -0.000719488 0.0026762 +EDGE3 1528 1579 -4.11958 10.32 -5.40336 -0.000534206 -0.000561206 0.129175 +EDGE3 1529 1578 -3.97951 -10.3438 -5.15125 0.000680004 -0.00588547 -0.11985 +EDGE3 1530 1580 -3.40098 -0.00105606 -5.29238 0.011396 -0.00252938 -0.000219337 +EDGE3 1529 1580 -4.1021 10.3302 -5.38094 0.00573539 0.00311866 0.127079 +EDGE3 1530 1579 -3.97088 -10.3188 -5.16034 0.0056419 -0.000797192 -0.129242 +EDGE3 1531 1581 -3.42034 0.00329908 -5.27842 -0.00453064 0.00553129 0.00898623 +EDGE3 1530 1581 -4.12337 10.3112 -5.38239 0.000212252 0.0109023 0.117867 +EDGE3 1531 1580 -3.98244 -10.3161 -5.17554 -0.00364167 0.00384518 -0.125796 +EDGE3 1532 1582 -3.40401 -0.00340569 -5.28169 -0.00236212 0.0108741 -0.00920726 +EDGE3 1531 1582 -4.11926 10.3051 -5.38965 -0.000743977 0.00403732 0.122942 +EDGE3 1532 1581 -3.9836 -10.3196 -5.16161 -0.00764835 4.23959e-07 -0.12947 +EDGE3 1532 1583 -4.14923 10.3001 -5.37444 0.0019876 -0.000524307 0.12386 +EDGE3 1533 1583 -3.419 0.00478358 -5.26824 -0.0111534 0.00264491 0.000834926 +EDGE3 1534 1584 -3.41742 -0.00965317 -5.27848 0.00514389 0.00203202 0.00447265 +EDGE3 1533 1582 -3.99271 -10.3024 -5.16068 0.00434773 -0.00457059 -0.121499 +EDGE3 1533 1584 -4.15746 10.2993 -5.36032 -0.000406942 -0.00318815 0.129705 +EDGE3 1534 1583 -3.9987 -10.2982 -5.16068 0.0100202 0.00270328 -0.12353 +EDGE3 1534 1585 -4.15452 10.2603 -5.39231 0.00376476 0.00942843 0.124241 +EDGE3 1535 1585 -3.44855 0.0104101 -5.25472 -0.00334833 0.001105 0.000590841 +EDGE3 1536 1586 -3.44359 0.00807536 -5.26747 -0.000436779 0.00540867 0.00397585 +EDGE3 1535 1584 -4.00931 -10.2858 -5.14283 -0.00226256 0.00264131 -0.128726 +EDGE3 1535 1586 -4.14666 10.2766 -5.35208 0.00278474 -0.0111599 0.128181 +EDGE3 1536 1585 -4.01625 -10.2662 -5.13981 0.00421605 0.00632556 -0.120024 +EDGE3 1537 1587 -3.42448 -0.0110733 -5.23678 0.00174395 5.6944e-05 -0.00400874 +EDGE3 1536 1587 -4.14178 10.2469 -5.35364 0.000661739 0.00564955 0.117664 +EDGE3 1537 1586 -4.01943 -10.264 -5.13549 -0.00727195 -0.0041039 -0.125564 +EDGE3 1538 1588 -3.46271 0.00850521 -5.25287 -0.00358368 0.00690107 0.0102687 +EDGE3 1537 1588 -4.18216 10.2354 -5.35544 0.00458422 -2.26849e-05 0.130176 +EDGE3 1538 1587 -4.03094 -10.2616 -5.12958 -0.00363635 0.00093301 -0.131194 +EDGE3 1539 1589 -3.47051 0.0137924 -5.23276 -0.00550052 -0.00356133 0.00266842 +EDGE3 1538 1589 -4.17403 10.2211 -5.35003 0.00011848 6.51655e-05 0.129304 +EDGE3 1539 1588 -4.05423 -10.2425 -5.14249 0.0046198 -0.00244445 -0.135124 +EDGE3 1540 1590 -3.47338 0.0102543 -5.23255 0.00594671 -0.00731492 -0.000326625 +EDGE3 1539 1590 -4.16545 10.2369 -5.34934 0.00353044 -0.0047535 0.127582 +EDGE3 1540 1589 -4.04492 -10.2607 -5.15216 0.00587927 0.00652872 -0.134766 +EDGE3 1541 1591 -3.46701 0.0161239 -5.22144 0.00392386 -0.00422728 -0.00225257 +EDGE3 1540 1591 -4.18589 10.2288 -5.32542 0.00903099 -0.00370088 0.125495 +EDGE3 1541 1590 -4.0235 -10.2539 -5.13625 -0.00664931 -0.00433508 -0.124062 +EDGE3 1542 1592 -3.48794 -0.0177374 -5.22544 -0.00503345 0.00239024 0.000739383 +EDGE3 1541 1592 -4.19093 10.2032 -5.33333 -0.00536194 -0.00310539 0.12844 +EDGE3 1542 1591 -4.05445 -10.2342 -5.13502 -0.00195033 0.00407667 -0.132097 +EDGE3 1543 1593 -3.50614 0.0185158 -5.22637 -0.00512266 0.00527582 -0.000611717 +EDGE3 1542 1593 -4.18936 10.2103 -5.32632 0.00682115 -0.00361692 0.125435 +EDGE3 1543 1592 -4.051 -10.2022 -5.13263 0.0065316 -0.00017318 -0.122974 +EDGE3 1544 1594 -3.47665 -0.0128518 -5.21434 0.00500287 0.00841703 0.00717886 +EDGE3 1543 1594 -4.20051 10.1872 -5.34651 0.000439003 -0.00867328 0.124202 +EDGE3 1544 1593 -4.06499 -10.2208 -5.11795 -0.00395725 0.00614111 -0.126486 +EDGE3 1545 1595 -3.50814 -0.00237698 -5.23488 -0.00753209 -0.00125116 0.00053873 +EDGE3 1544 1595 -4.2086 10.1807 -5.33493 0.0012244 -0.00323351 0.132332 +EDGE3 1545 1594 -4.06151 -10.1914 -5.12815 -0.00319476 0.00305291 -0.126316 +EDGE3 1546 1596 -3.49879 0.005337 -5.23274 -0.00564999 -0.000189178 -0.00178393 +EDGE3 1545 1596 -4.2167 10.1782 -5.33448 0.00484774 0.00640722 0.104011 +EDGE3 1546 1595 -4.06389 -10.1863 -5.1092 -0.0039497 0.0148032 -0.119784 +EDGE3 1547 1597 -3.51372 0.00722538 -5.20909 0.00744458 0.0018121 -0.00183942 +EDGE3 1546 1597 -4.22051 10.1714 -5.29094 0.00130869 -0.00102566 0.126046 +EDGE3 1547 1596 -4.08792 -10.1748 -5.11813 0.00204926 -0.00530436 -0.12997 +EDGE3 1548 1598 -3.50479 0.00621142 -5.20466 -0.00372875 0.00108067 0.00266563 +EDGE3 1547 1598 -4.19771 10.1487 -5.30637 0.00022862 0.00559654 0.123098 +EDGE3 1548 1597 -4.09161 -10.1438 -5.10069 -0.00920407 0.00354411 -0.12142 +EDGE3 1549 1599 -3.51504 -0.000490628 -5.20989 -0.0033466 -0.00268342 0.00292676 +EDGE3 1548 1599 -4.24672 10.1414 -5.31646 9.82282e-05 -0.00483092 0.124838 +EDGE3 1549 1598 -4.09714 -10.1631 -5.1054 -0.00159799 0.00909769 -0.12626 +EDGE3 1550 1600 -3.5486 -0.00457299 -5.19774 -0.00230505 0.00335795 -0.00228513 +EDGE3 1549 1600 -4.23121 10.1462 -5.30409 0.00518272 0.000923541 0.127578 +EDGE3 1550 1599 -4.10665 -10.1607 -5.08864 0.00552679 -0.00852642 -0.133313 +EDGE3 1551 1601 -3.54084 0.00651771 -5.18653 0.000651289 0.00660348 -0.00201501 +EDGE3 1550 1601 -4.25016 10.115 -5.28893 -0.00468987 -0.000985931 0.12056 +EDGE3 1551 1600 -4.08451 -10.1507 -5.0917 0.00769748 0.0110564 -0.125445 +EDGE3 1552 1602 -3.54198 -2.24158e-05 -5.17712 -0.000383331 -0.00161238 0.00661999 +EDGE3 1551 1602 -4.24267 10.1176 -5.28623 -0.00117055 -0.00197258 0.129236 +EDGE3 1552 1601 -4.13103 -10.1217 -5.08951 0.00033323 -0.00186568 -0.132823 +EDGE3 1553 1603 -3.55843 -0.015959 -5.18961 8.99238e-05 0.0018957 -0.00550412 +EDGE3 1552 1603 -4.25386 10.1179 -5.28909 0.00959944 0.00175008 0.123593 +EDGE3 1553 1602 -4.11096 -10.1274 -5.09035 0.00417524 -0.0065092 -0.119383 +EDGE3 1554 1604 -3.55497 -0.0227741 -5.17836 -0.00264439 -0.00335857 0.00499885 +EDGE3 1553 1604 -4.26064 10.0967 -5.28384 0.0034592 0.00162139 0.121355 +EDGE3 1554 1603 -4.11302 -10.1062 -5.07979 -0.00110317 -0.00328774 -0.114964 +EDGE3 1555 1605 -3.56658 0.00793922 -5.1696 -0.00383581 -0.00230736 -0.00574036 +EDGE3 1554 1605 -4.27088 10.0829 -5.27072 0.0014014 0.0151262 0.120833 +EDGE3 1555 1604 -4.11574 -10.1043 -5.06228 -0.00383071 -0.00708338 -0.120548 +EDGE3 1556 1606 -3.57577 -0.00447534 -5.17356 0.00835564 0.00381643 -0.00698677 +EDGE3 1555 1606 -4.27801 10.0691 -5.26523 0.0115115 -0.00931568 0.137703 +EDGE3 1556 1605 -4.12703 -10.0883 -5.09197 0.00671173 -0.000176923 -0.132291 +EDGE3 1557 1607 -3.58396 0.00174595 -5.16111 0.00865732 -0.00223042 -0.00299596 +EDGE3 1556 1607 -4.27492 10.0562 -5.29007 -0.00293235 0.00277373 0.129742 +EDGE3 1557 1606 -4.11649 -10.0886 -5.07298 0.00144571 -0.00511342 -0.125331 +EDGE3 1558 1608 -3.58125 -0.010535 -5.15039 -0.00845936 0.00356933 0.00809502 +EDGE3 1557 1608 -4.28308 10.0567 -5.26185 0.00285206 0.00280926 0.125574 +EDGE3 1558 1607 -4.14292 -10.0859 -5.07721 0.00820477 0.00301233 -0.131683 +EDGE3 1559 1609 -3.59166 -0.00453603 -5.15315 -0.00557638 -0.000722837 0.00365262 +EDGE3 1558 1609 -4.27633 10.0472 -5.24097 -0.00441473 -0.000655872 0.115957 +EDGE3 1559 1608 -4.14118 -10.0545 -5.07759 -0.00596223 0.000731022 -0.12798 +EDGE3 1560 1610 -3.60225 0.00109229 -5.15316 0.00244746 -0.00460946 -0.00397078 +EDGE3 1559 1610 -4.28823 10.0208 -5.25919 0.0104509 -0.000207764 0.126008 +EDGE3 1560 1609 -4.15606 -10.0494 -5.05176 -0.0103474 -0.00342577 -0.126815 +EDGE3 1561 1611 -3.60218 0.00713124 -5.13789 -0.00567102 0.00759685 -0.00404257 +EDGE3 1560 1611 -4.29815 10.0123 -5.24596 0.00277882 0.00165496 0.124892 +EDGE3 1561 1610 -4.1631 -10.0478 -5.04061 0.000980271 2.07974e-05 -0.125795 +EDGE3 1562 1612 -3.61696 -0.0117821 -5.14919 -0.00269482 0.00509413 0.0009991 +EDGE3 1561 1612 -4.3112 10.0423 -5.26323 0.0100738 -0.002098 0.136887 +EDGE3 1562 1611 -4.15386 -10.0363 -5.03296 0.00194362 5.16783e-05 -0.13062 +EDGE3 1563 1613 -3.61386 -0.0187535 -5.14943 -0.00283247 -0.000875852 0.00604299 +EDGE3 1562 1613 -4.31913 10.0264 -5.25386 -0.000944142 0.0132116 0.119275 +EDGE3 1563 1612 -4.17547 -10.0338 -5.04718 -0.000953939 -0.00124026 -0.11551 +EDGE3 1564 1614 -3.59893 0.000347666 -5.16368 0.00235266 0.00479079 -0.00614983 +EDGE3 1563 1614 -4.31001 10.0269 -5.23595 -0.00337322 0.00210896 0.13337 +EDGE3 1564 1613 -4.188 -10.0269 -5.02224 -0.00662665 -0.00196513 -0.123873 +EDGE3 1565 1615 -3.63852 -0.00809265 -5.12297 0.00749197 0.000194488 0.00444775 +EDGE3 1564 1615 -4.33226 9.98638 -5.24037 0.00659021 -0.00208322 0.127606 +EDGE3 1565 1614 -4.17803 -10.0073 -5.01677 -0.0012669 0.000444184 -0.112392 +EDGE3 1566 1616 -3.63558 -0.0115986 -5.11558 0.000566981 -0.00462995 -0.00203157 +EDGE3 1565 1616 -4.34072 9.98845 -5.23968 -0.00283773 0.00273047 0.119764 +EDGE3 1566 1615 -4.19591 -10.0038 -5.02937 0.000199725 -0.005714 -0.117423 +EDGE3 1567 1617 -3.64549 0.00833295 -5.1218 -0.00807483 0.00984566 -0.0120979 +EDGE3 1566 1617 -4.32957 9.97276 -5.20587 -0.00124934 -0.00712589 0.132043 +EDGE3 1567 1616 -4.20324 -9.99229 -5.01938 -0.0018071 -0.00410816 -0.129028 +EDGE3 1568 1618 -3.63863 -0.0223329 -5.10543 0.00554618 -0.00374767 0.00429557 +EDGE3 1567 1618 -4.3531 10.0019 -5.23221 0.00387609 0.00458024 0.124095 +EDGE3 1568 1617 -4.21769 -9.98291 -5.01326 0.00209628 0.00088263 -0.126003 +EDGE3 1569 1619 -3.65607 -0.00325904 -5.14146 0.00987582 -0.000217701 0.00390824 +EDGE3 1568 1619 -4.33654 9.9701 -5.22477 0.00946067 -0.00549976 0.126217 +EDGE3 1569 1618 -4.20168 -9.97804 -5.00424 0.00147757 0.00327524 -0.117971 +EDGE3 1570 1620 -3.66489 0.0036406 -5.07753 -0.000128338 0.00503447 -0.00252402 +EDGE3 1569 1620 -4.34971 9.95258 -5.22206 -0.0052996 -0.00432465 0.128479 +EDGE3 1570 1619 -4.2148 -9.96691 -4.99245 -0.00723335 -0.00237562 -0.125498 +EDGE3 1571 1621 -3.65884 -0.00204754 -5.09508 -0.00334448 0.00606279 0.0054563 +EDGE3 1570 1621 -4.37346 9.93056 -5.20447 -0.00643748 -0.000714429 0.122856 +EDGE3 1571 1620 -4.20833 -9.94912 -4.99969 -0.00241584 -0.00303973 -0.12704 +EDGE3 1572 1622 -3.67668 -0.000273047 -5.0902 0.00182117 0.00896585 -0.000133226 +EDGE3 1571 1622 -4.35811 9.92213 -5.19569 0.00535566 0.00179217 0.116389 +EDGE3 1572 1621 -4.23336 -9.93144 -4.9927 -0.00286386 0.00368305 -0.125359 +EDGE3 1573 1623 -3.68681 -0.00250702 -5.0815 -0.000155244 -0.0102104 0.00168284 +EDGE3 1572 1623 -4.37351 9.90817 -5.18192 0.00431626 -0.00188128 0.125551 +EDGE3 1573 1622 -4.23791 -9.94905 -5.00083 0.00594152 -0.00310358 -0.125767 +EDGE3 1574 1624 -3.68194 0.0277759 -5.08948 0.00428177 -0.0025496 -0.00413333 +EDGE3 1573 1624 -4.38004 9.91368 -5.21025 -0.00478456 -0.00129474 0.125799 +EDGE3 1574 1623 -4.22879 -9.92741 -4.97574 -0.00285701 -0.000420778 -0.120357 +EDGE3 1575 1625 -3.69096 -0.0155177 -5.08941 0.00390224 -0.0102742 -0.0111715 +EDGE3 1575 1624 -4.23447 -9.91422 -4.98771 0.000465281 0.00443171 -0.131542 +EDGE3 1574 1625 -4.38838 9.90262 -5.17718 0.0030368 0.000933561 0.130047 +EDGE3 1576 1626 -3.69715 0.0208306 -5.06463 -0.00363674 0.00598707 -0.00325849 +EDGE3 1575 1626 -4.39394 9.87695 -5.18922 -0.00908629 -0.00332406 0.123388 +EDGE3 1576 1625 -4.2251 -9.89839 -4.98715 0.00631258 -0.00764712 -0.122105 +EDGE3 1577 1627 -3.67702 -0.0073592 -5.0752 -0.00327451 0.000705054 0.00448849 +EDGE3 1576 1627 -4.39969 9.88706 -5.18089 0.000118136 0.00376572 0.123971 +EDGE3 1577 1626 -4.24159 -9.88172 -4.97347 -0.0102284 -0.00633775 -0.12584 +EDGE3 1578 1628 -3.70567 -0.0113893 -5.07409 -0.00567536 0.00224146 -0.00758111 +EDGE3 1577 1628 -4.40214 9.85511 -5.17507 0.0082417 -0.00365676 0.124644 +EDGE3 1578 1627 -4.25578 -9.87726 -4.97108 0.00532486 0.00419119 -0.123594 +EDGE3 1579 1629 -3.71576 -0.00450309 -5.068 -0.00321693 -0.00381938 0.00172204 +EDGE3 1578 1629 -4.41017 9.8686 -5.16882 -0.0102332 0.00526992 0.126761 +EDGE3 1579 1628 -4.27373 -9.8694 -4.97428 -0.00813568 0.000802336 -0.119837 +EDGE3 1580 1630 -3.75439 -0.00319996 -5.04419 -0.00186309 0.00187137 -0.0026375 +EDGE3 1579 1630 -4.42355 9.85081 -5.16578 0.00100831 0.00177365 0.120428 +EDGE3 1580 1629 -4.26082 -9.84837 -4.96824 -0.0031334 0.00200489 -0.128 +EDGE3 1581 1631 -3.7212 -0.000697159 -5.06569 -0.00189508 -0.000939372 0.000852838 +EDGE3 1580 1631 -4.43093 9.84553 -5.15157 -0.0042398 -0.00341078 0.119283 +EDGE3 1581 1630 -4.29243 -9.84308 -4.95389 4.81824e-05 -0.000136307 -0.12242 +EDGE3 1582 1632 -3.72452 -0.00560368 -5.04324 0.00131369 -0.00155312 0.00301684 +EDGE3 1581 1632 -4.40875 9.83571 -5.1613 0.00763272 0.00296895 0.129753 +EDGE3 1582 1631 -4.28017 -9.8472 -4.96149 0.0095609 -0.00708034 -0.125916 +EDGE3 1583 1633 -3.73172 -0.0162012 -5.04554 -0.00682975 -0.00391761 0.0014282 +EDGE3 1582 1633 -4.4374 9.83096 -5.13992 -0.000488877 0.000266369 0.130164 +EDGE3 1583 1632 -4.28224 -9.83964 -4.93376 0.00823306 -0.00280928 -0.123182 +EDGE3 1584 1634 -3.75424 -0.00336306 -5.05923 0.00210903 0.00483504 -0.00568784 +EDGE3 1583 1634 -4.45011 9.83103 -5.14388 0.00832388 0.00410714 0.128949 +EDGE3 1584 1633 -4.29431 -9.81341 -4.95049 0.00768538 0.00599256 -0.122757 +EDGE3 1585 1635 -3.74725 0.0112293 -5.04271 0.00305862 -0.00317051 0.0024212 +EDGE3 1584 1635 -4.44898 9.81173 -5.13712 -0.00277218 -0.00362231 0.132735 +EDGE3 1585 1634 -4.28859 -9.82615 -4.9391 -0.00728193 0.00143582 -0.117516 +EDGE3 1586 1636 -3.76101 -0.00568854 -5.03214 6.27705e-05 0.00443087 0.00966438 +EDGE3 1585 1636 -4.47052 9.79616 -5.11843 0.000170057 0.00271954 0.125613 +EDGE3 1586 1635 -4.29649 -9.81523 -4.93209 0.00783502 5.50231e-05 -0.116897 +EDGE3 1587 1637 -3.78249 0.025841 -5.03187 0.00843805 0.00183528 -0.00132881 +EDGE3 1586 1637 -4.45501 9.78184 -5.13492 0.00643344 0.00637727 0.125311 +EDGE3 1587 1636 -4.30509 -9.77796 -4.93474 -0.0101508 0.00135915 -0.127815 +EDGE3 1588 1638 -3.76709 -0.0354175 -5.00696 -0.00111361 0.00301297 -0.00431112 +EDGE3 1587 1638 -4.45844 9.78118 -5.14089 0.0064112 0.00638984 0.122961 +EDGE3 1588 1637 -4.30605 -9.78228 -4.93068 -0.00871881 -0.00263805 -0.130626 +EDGE3 1589 1639 -3.78687 -0.00545199 -5.015 0.00319818 0.0084814 -0.00754055 +EDGE3 1588 1639 -4.46418 9.76781 -5.11293 0.00194175 0.00645614 0.122199 +EDGE3 1589 1638 -4.32508 -9.77812 -4.9272 0.00498539 0.0026815 -0.121972 +EDGE3 1590 1640 -3.77499 0.0128417 -5.02824 0.00562934 -0.00125981 -0.00310495 +EDGE3 1589 1640 -4.47535 9.76999 -5.11114 -0.00160123 -0.000992001 0.123543 +EDGE3 1590 1639 -4.31816 -9.79303 -4.92218 -0.000593397 0.00219419 -0.129369 +EDGE3 1591 1641 -3.77999 -0.00513835 -5.01499 0.00442537 -0.00708843 -0.00213608 +EDGE3 1590 1641 -4.4773 9.74917 -5.10758 -0.00183636 -0.0121756 0.125662 +EDGE3 1591 1640 -4.32235 -9.75032 -4.90054 0.00736679 0.00625114 -0.122595 +EDGE3 1592 1642 -3.80954 -0.0084493 -5.0083 0.000178729 0.00130686 -0.000446485 +EDGE3 1591 1642 -4.47132 9.74179 -5.09645 0.00481824 -0.000992736 0.12796 +EDGE3 1592 1641 -4.33361 -9.7614 -4.91923 -0.00402785 -0.00167439 -0.119664 +EDGE3 1593 1643 -3.79669 -0.00487926 -4.98624 -0.00237493 0.00194472 -0.00515592 +EDGE3 1592 1643 -4.48248 9.72588 -5.09084 0.00410064 -0.00533484 0.129115 +EDGE3 1593 1642 -4.32317 -9.74794 -4.89268 -0.00121421 0.00529443 -0.120689 +EDGE3 1594 1644 -3.79829 0.00733203 -4.97973 0.000138846 0.00562365 -0.000785532 +EDGE3 1593 1644 -4.49893 9.70819 -5.0968 0.00807222 -0.00933257 0.125534 +EDGE3 1594 1643 -4.33829 -9.72423 -4.903 0.00484578 -0.000306859 -0.138266 +EDGE3 1595 1645 -3.80703 0.00588682 -4.98329 0.0118057 0.00347943 0.00653672 +EDGE3 1594 1645 -4.51139 9.7108 -5.08955 0.00148847 -0.000853383 0.129621 +EDGE3 1595 1644 -4.3715 -9.70137 -4.90687 -0.00172957 0.000322231 -0.131124 +EDGE3 1596 1646 -3.8331 -0.0120778 -4.9876 0.00245894 0.00558116 0.00594644 +EDGE3 1595 1646 -4.50758 9.70524 -5.09598 0.00498739 0.00510976 0.123939 +EDGE3 1596 1645 -4.36013 -9.6991 -4.88764 -0.00139339 -0.00471071 -0.12667 +EDGE3 1597 1647 -3.83884 0.0102509 -4.97043 0.00712105 -0.0085306 0.013209 +EDGE3 1596 1647 -4.5082 9.69892 -5.078 -0.00101281 -0.00751629 0.125579 +EDGE3 1597 1646 -4.35886 -9.70868 -4.87876 0.00748341 0.00213334 -0.122628 +EDGE3 1598 1648 -3.8318 -0.00815436 -4.98051 -0.00664425 0.00289468 0.00364071 +EDGE3 1597 1648 -4.51111 9.67572 -5.07839 -0.00276294 -0.00687825 0.126018 +EDGE3 1598 1647 -4.3724 -9.68934 -4.8581 -0.00143469 -0.00445708 -0.116043 +EDGE3 1599 1649 -3.84648 0.00294916 -4.97196 -0.000154761 0.00270961 0.00421454 +EDGE3 1598 1649 -4.53086 9.66892 -5.06702 -0.00348607 0.000506811 0.127946 +EDGE3 1599 1648 -4.36344 -9.67959 -4.89891 0.0106584 -0.00325624 -0.12872 +EDGE3 1600 1650 -3.84611 0.00532477 -4.96708 -0.00169042 -0.000349913 -0.00220924 +EDGE3 1599 1650 -4.55602 9.66025 -5.05637 -0.00141408 0.000113175 0.128437 +EDGE3 1600 1649 -4.37781 -9.65817 -4.87188 0.00662239 -0.000275053 -0.128305 +EDGE3 1601 1651 -3.8513 0.0113764 -4.94999 -0.0061232 0.00460027 -0.00568099 +EDGE3 1600 1651 -4.54492 9.6474 -5.06231 -0.00525688 -0.000615266 0.129299 +EDGE3 1601 1650 -4.39566 -9.67067 -4.86485 0.00883199 0.00576233 -0.125805 +EDGE3 1602 1652 -3.85478 0.00758804 -4.9627 0.00022468 0.00127617 -0.00319257 +EDGE3 1601 1652 -4.53982 9.65809 -5.0522 -0.00916124 -0.00138225 0.125395 +EDGE3 1602 1651 -4.39069 -9.65869 -4.84952 -0.00900722 -0.000635133 -0.131854 +EDGE3 1603 1653 -3.87046 0.0161229 -4.9437 0.00251149 -0.000519272 -9.6468e-05 +EDGE3 1603 1652 -4.39003 -9.63958 -4.87313 -0.00238476 0.0126247 -0.131061 +EDGE3 1602 1653 -4.55192 9.62114 -5.06472 -0.00267707 -0.00437478 0.124827 +EDGE3 1604 1654 -3.87796 0.00437226 -4.93994 0.00181987 0.000406541 0.00342671 +EDGE3 1603 1654 -4.55304 9.60363 -5.05079 -0.00223277 -0.00683736 0.127783 +EDGE3 1604 1653 -4.4132 -9.59965 -4.84094 0.000462323 0.00408481 -0.129155 +EDGE3 1605 1655 -3.88744 -0.00251837 -4.92587 -0.00593637 -0.00754208 -0.000820626 +EDGE3 1604 1655 -4.56577 9.60065 -5.06254 0.00355252 -0.00914061 0.122972 +EDGE3 1605 1654 -4.39123 -9.61191 -4.83785 0.00510909 0.00130826 -0.124184 +EDGE3 1606 1656 -3.87438 0.0101672 -4.92964 0.0124174 -0.00166266 -0.00293387 +EDGE3 1605 1656 -4.58149 9.58782 -5.04326 -0.0120995 0.00458057 0.127106 +EDGE3 1606 1655 -4.4194 -9.60015 -4.85211 -0.00480755 0.00465923 -0.128022 +EDGE3 1607 1657 -3.89379 0.00245333 -4.93871 0.00546673 -0.00170363 -0.00652245 +EDGE3 1606 1657 -4.56214 9.57573 -5.03707 -0.00970359 0.0149588 0.129096 +EDGE3 1607 1656 -4.42483 -9.59559 -4.85549 -0.00623762 0.00204651 -0.129437 +EDGE3 1608 1658 -3.89987 -1.0974e-05 -4.93195 -0.00237009 -0.00136713 0.00643543 +EDGE3 1607 1658 -4.58025 9.58177 -5.02454 0.000537245 0.00747947 0.134875 +EDGE3 1608 1657 -4.42236 -9.58055 -4.83065 -0.00379324 0.00398092 -0.126188 +EDGE3 1609 1659 -3.89956 -0.00901992 -4.90905 0.00405656 0.00738194 -0.0012287 +EDGE3 1608 1659 -4.58635 9.57397 -5.0138 -0.00974519 0.00371477 0.124357 +EDGE3 1609 1658 -4.42647 -9.56584 -4.80593 0.00475952 0.00321777 -0.12015 +EDGE3 1610 1660 -3.90992 0.0109984 -4.92949 -0.00651641 -0.00555888 -0.00581141 +EDGE3 1609 1660 -4.59892 9.54755 -5.01564 0.00335306 0.00544187 0.130964 +EDGE3 1611 1661 -3.92781 -0.00613803 -4.91589 -0.00619414 0.00409828 -0.00281478 +EDGE3 1610 1659 -4.42344 -9.559 -4.83806 -0.00547621 0.00308555 -0.127486 +EDGE3 1610 1661 -4.60524 9.54465 -4.99244 -0.000469769 0.00149334 0.120851 +EDGE3 1611 1660 -4.42915 -9.54408 -4.8232 -0.000126211 -0.00175912 -0.120697 +EDGE3 1612 1662 -3.91633 -0.0124472 -4.91749 -0.00406552 0.00843814 -0.0123728 +EDGE3 1611 1662 -4.61043 9.53032 -4.99424 -0.000497285 -0.0125333 0.125973 +EDGE3 1612 1661 -4.43645 -9.5433 -4.81499 0.00267307 0.00464573 -0.122974 +EDGE3 1613 1663 -3.92673 -0.0132193 -4.90796 0.00426951 -0.000299844 0.00227193 +EDGE3 1612 1663 -4.59507 9.50162 -4.99065 0.00620364 0.00149274 0.124553 +EDGE3 1613 1662 -4.43998 -9.52409 -4.79696 0.00698627 0.00142086 -0.118162 +EDGE3 1614 1664 -3.94163 0.00562102 -4.88702 0.00903647 -0.00419683 -0.00712273 +EDGE3 1613 1664 -4.60426 9.52017 -5.02713 -0.00136018 0.00160621 0.129315 +EDGE3 1614 1663 -4.47307 -9.52156 -4.8225 -0.00480471 0.0101714 -0.121253 +EDGE3 1615 1665 -3.94243 0.0148857 -4.88517 -0.0056056 -0.00977625 -0.0051089 +EDGE3 1614 1665 -4.61163 9.50258 -4.9902 0.00512015 0.00244481 0.125817 +EDGE3 1615 1664 -4.46966 -9.52855 -4.80647 -0.00565945 -0.00308159 -0.115502 +EDGE3 1616 1666 -3.93784 -0.0155383 -4.86916 0.00164762 -0.00257413 0.000368295 +EDGE3 1615 1666 -4.61559 9.48753 -4.97239 -0.00194664 0.00519152 0.116713 +EDGE3 1616 1665 -4.46388 -9.49221 -4.79705 -0.00436074 -0.00696153 -0.129546 +EDGE3 1617 1667 -3.97883 -0.0197636 -4.88774 -0.00401697 0.00293286 -0.000603886 +EDGE3 1616 1667 -4.63354 9.48996 -4.98208 -0.00756494 0.00487015 0.128687 +EDGE3 1617 1666 -4.4876 -9.48705 -4.77472 0.00218672 -0.00229369 -0.125765 +EDGE3 1618 1668 -3.97271 0.00776969 -4.87429 0.000581721 0.0010377 -0.00271537 +EDGE3 1617 1668 -4.62691 9.46882 -4.98098 0.00134972 0.00552661 0.123666 +EDGE3 1618 1667 -4.4894 -9.49842 -4.77308 -0.00162933 -0.00175811 -0.128903 +EDGE3 1618 1669 -4.65691 9.45629 -4.97252 0.00280243 -0.00160276 0.12832 +EDGE3 1619 1669 -3.98 -0.0117081 -4.87815 0.00489591 -0.00820726 -0.00104268 +EDGE3 1620 1670 -3.98923 0.000797487 -4.87571 -0.00120427 -0.000262362 -0.00101235 +EDGE3 1619 1668 -4.48693 -9.48012 -4.77591 -0.00776969 -0.00309525 -0.133152 +EDGE3 1619 1670 -4.64215 9.43774 -4.97612 0.000649623 -0.000752692 0.135071 +EDGE3 1620 1669 -4.48376 -9.45602 -4.77713 -0.00433503 -0.00282895 -0.129813 +EDGE3 1620 1671 -4.65229 9.45587 -4.95804 -0.00239903 -0.00686543 0.127165 +EDGE3 1621 1671 -3.97509 -0.0118297 -4.87814 0.0126478 0.00412022 0.00251274 +EDGE3 1622 1672 -3.98526 -0.0177136 -4.83881 0.00827507 0.00189754 -0.00223825 +EDGE3 1621 1670 -4.5135 -9.45745 -4.76577 -8.53624e-05 0.00595202 -0.124067 +EDGE3 1621 1672 -4.66865 9.41752 -4.94886 0.00893193 -0.00141095 0.122803 +EDGE3 1622 1671 -4.49693 -9.44967 -4.74062 0.00342196 -0.000223064 -0.12353 +EDGE3 1623 1673 -3.99664 0.00628349 -4.83175 -0.00414502 -0.00517431 0.000111258 +EDGE3 1622 1673 -4.65593 9.43365 -4.94363 0.00212768 -0.00208231 0.114291 +EDGE3 1623 1672 -4.50628 -9.45179 -4.7429 -0.00297348 -0.00183553 -0.127395 +EDGE3 1624 1674 -3.99917 -0.00779385 -4.84656 0.000911287 -0.00328539 -0.000417498 +EDGE3 1623 1674 -4.67481 9.41214 -4.94524 0.000582349 0.00774535 0.127792 +EDGE3 1624 1673 -4.51775 -9.41163 -4.74162 -0.00403379 0.000744766 -0.135055 +EDGE3 1625 1675 -4.00333 -0.000140422 -4.85168 -0.0089873 0.00691374 -0.00115273 +EDGE3 1624 1675 -4.68924 9.39937 -4.94442 -0.0010351 -0.0105123 0.126767 +EDGE3 1625 1674 -4.50154 -9.40822 -4.74045 0.00265831 0.00317324 -0.119576 +EDGE3 1626 1676 -4.02287 0.012495 -4.83114 -0.00278188 -0.00289634 -0.00104604 +EDGE3 1625 1676 -4.67965 9.39081 -4.93359 -0.0059135 0.00508385 0.128124 +EDGE3 1626 1675 -4.51653 -9.40352 -4.75607 -0.00270745 -0.00546044 -0.123292 +EDGE3 1627 1677 -3.99763 -0.00245704 -4.83577 -9.80161e-05 0.00257592 -0.00287151 +EDGE3 1626 1677 -4.68509 9.38198 -4.92877 -0.00450047 0.00213519 0.115517 +EDGE3 1627 1676 -4.52462 -9.38839 -4.74712 -0.00487194 -0.00391941 -0.130653 +EDGE3 1628 1678 -4.03484 -0.0183107 -4.82184 -0.00804835 0.00135442 0.00739713 +EDGE3 1627 1678 -4.69611 9.34692 -4.93745 -0.00219465 -0.0059534 0.122988 +EDGE3 1628 1677 -4.51966 -9.37559 -4.74429 0.00266177 -0.00229253 -0.126332 +EDGE3 1629 1679 -4.02125 0.00625129 -4.81566 0.000598033 -0.00233915 0.00171649 +EDGE3 1628 1679 -4.68931 9.35371 -4.91219 0.0130683 -0.000373924 0.131694 +EDGE3 1629 1678 -4.52768 -9.38333 -4.73606 -0.00279817 0.000117254 -0.122069 +EDGE3 1630 1680 -4.03967 -0.00139867 -4.81292 -0.000580549 0.00202522 -0.000341753 +EDGE3 1629 1680 -4.70824 9.36302 -4.91046 -0.00412525 -0.0092872 0.120376 +EDGE3 1630 1679 -4.54718 -9.36024 -4.72156 0.00320506 -3.92127e-05 -0.127854 +EDGE3 1630 1681 -4.71358 9.35439 -4.90221 -0.00193992 -0.00408454 0.128857 +EDGE3 1631 1681 -4.03825 0.00315734 -4.80285 0.013327 -0.00431499 0.00452881 +EDGE3 1632 1682 -4.05285 -0.0145719 -4.8051 -0.012195 0.00106982 -0.004883 +EDGE3 1631 1680 -4.54791 -9.34692 -4.71791 -0.0105815 -0.00119107 -0.119481 +EDGE3 1632 1681 -4.54563 -9.33722 -4.70981 -0.000764211 -0.001677 -0.135726 +EDGE3 1631 1682 -4.72514 9.31124 -4.88997 0.00659377 -0.00181575 0.12787 +EDGE3 1633 1683 -4.04304 0.00335139 -4.79467 -0.00649554 0.00484032 -0.000422035 +EDGE3 1632 1683 -4.72196 9.32952 -4.88957 0.000750125 -0.00384828 0.130662 +EDGE3 1633 1682 -4.58285 -9.32197 -4.70761 -0.00596873 -0.000594463 -0.122457 +EDGE3 1634 1684 -4.07387 0.0111983 -4.8134 -0.00433656 -0.00192932 -0.00208496 +EDGE3 1633 1684 -4.72054 9.29662 -4.90427 -0.00720318 0.000286951 0.131914 +EDGE3 1635 1685 -4.05741 0.00103706 -4.81859 0.00159753 -0.00973163 -0.00651118 +EDGE3 1634 1683 -4.57002 -9.30933 -4.71695 0.00459697 -0.00179441 -0.133061 +EDGE3 1634 1685 -4.7216 9.2857 -4.87873 0.000847842 0.0018345 0.121408 +EDGE3 1635 1684 -4.56397 -9.29504 -4.67566 -0.00263603 0.00262498 -0.133278 +EDGE3 1636 1686 -4.07555 -0.0162079 -4.78054 -0.00299907 0.00608257 -0.00944236 +EDGE3 1635 1686 -4.7314 9.2784 -4.89338 -0.00354054 0.000790252 0.116462 +EDGE3 1636 1685 -4.55801 -9.29924 -4.68792 -0.00397368 -0.00549765 -0.118925 +EDGE3 1637 1687 -4.07923 -0.00350271 -4.76532 0.00342348 -0.00380505 -0.00767802 +EDGE3 1636 1687 -4.72438 9.28153 -4.876 0.00229911 0.0148171 0.120429 +EDGE3 1637 1686 -4.56796 -9.28451 -4.68346 0.00166627 0.00400281 -0.126585 +EDGE3 1638 1688 -4.09405 -0.00610734 -4.78026 -0.00740239 0.00790395 -0.00271591 +EDGE3 1637 1688 -4.74235 9.27104 -4.87224 0.00174379 -0.000168789 0.122583 +EDGE3 1638 1687 -4.58994 -9.26582 -4.68626 -0.0142717 -0.00126655 -0.128016 +EDGE3 1639 1689 -4.08748 0.00271527 -4.75022 0.00583557 0.0107021 -0.00423942 +EDGE3 1638 1689 -4.75791 9.24075 -4.87021 0.0035844 0.0010868 0.125949 +EDGE3 1639 1688 -4.58396 -9.26978 -4.66311 0.00231667 -0.0101319 -0.12417 +EDGE3 1640 1690 -4.09246 0.0137696 -4.75538 -0.00415834 -0.000803347 0.00585186 +EDGE3 1639 1690 -4.75768 9.24953 -4.85259 -0.00173352 -0.00606551 0.121507 +EDGE3 1640 1689 -4.61043 -9.26215 -4.68657 -0.00469416 0.00461811 -0.11659 +EDGE3 1641 1691 -4.10442 -0.00148162 -4.76836 0.00655073 0.00298054 -0.00234923 +EDGE3 1640 1691 -4.78386 9.24198 -4.86163 0.00802861 -0.000618831 0.126296 +EDGE3 1641 1690 -4.59637 -9.24189 -4.66707 0.00329474 -0.00291547 -0.122059 +EDGE3 1642 1692 -4.10664 0.00675134 -4.74294 0.000689346 -0.00740033 0.00160381 +EDGE3 1641 1692 -4.78308 9.2237 -4.85952 -0.00268856 -0.00148306 0.129273 +EDGE3 1642 1691 -4.59387 -9.23314 -4.6582 0.00153889 -0.00413263 -0.130297 +EDGE3 1643 1693 -4.10874 0.0119689 -4.73683 -0.00227162 -9.01147e-05 -0.00155296 +EDGE3 1642 1693 -4.7619 9.20961 -4.86523 -0.000578616 0.00980701 0.132072 +EDGE3 1643 1692 -4.61047 -9.21015 -4.67069 -0.00401153 0.0109526 -0.119774 +EDGE3 1644 1694 -4.13181 -0.0132752 -4.73285 -0.00543076 0.00676282 0.00539137 +EDGE3 1643 1694 -4.76187 9.18479 -4.83369 0.00132399 8.10511e-05 0.121896 +EDGE3 1644 1693 -4.60481 -9.22826 -4.65285 -0.00412914 0.00661897 -0.127643 +EDGE3 1645 1695 -4.13114 0.00142796 -4.73794 -0.00140266 0.000365451 0.00257162 +EDGE3 1644 1695 -4.78101 9.19467 -4.83363 0.00650734 -0.00908859 0.12591 +EDGE3 1645 1694 -4.61674 -9.19333 -4.65474 -0.00555638 0.00572368 -0.113151 +EDGE3 1646 1696 -4.134 0.0199297 -4.72526 0.00500178 0.00308011 0.00210791 +EDGE3 1645 1696 -4.79365 9.172 -4.82676 0.00590847 -0.000181931 0.123266 +EDGE3 1646 1695 -4.61604 -9.1995 -4.65888 0.00504131 -0.00509462 -0.121523 +EDGE3 1647 1697 -4.14292 -0.0260781 -4.73819 -0.00689312 -0.00643783 0.00734653 +EDGE3 1646 1697 -4.78817 9.1523 -4.82262 -0.00402016 -0.000346618 0.132817 +EDGE3 1647 1696 -4.62892 -9.18279 -4.64463 -0.00770817 0.00835736 -0.114446 +EDGE3 1648 1698 -4.13072 -0.0190185 -4.72763 -0.00566104 -0.00123399 0.00191498 +EDGE3 1647 1698 -4.80149 9.1715 -4.83527 0.0011605 0.00589671 0.121789 +EDGE3 1648 1697 -4.64154 -9.17741 -4.63158 -0.00111146 0.00614007 -0.123479 +EDGE3 1649 1699 -4.13743 0.00796612 -4.70326 -0.00112035 0.000537442 0.00336731 +EDGE3 1648 1699 -4.8148 9.1444 -4.8087 -0.00289327 0.0100136 0.129582 +EDGE3 1649 1698 -4.63987 -9.14915 -4.62477 0.00281841 -0.00107355 -0.126794 +EDGE3 1650 1700 -4.17127 -0.00825053 -4.71219 0.00485208 0.00407436 -0.000560418 +EDGE3 1649 1700 -4.80464 9.14012 -4.81456 0.00897 0.00287857 0.131535 +EDGE3 1650 1699 -4.64773 -9.16814 -4.60182 0.00576954 -0.00310573 -0.125887 +EDGE3 1651 1701 -4.14831 -0.00551818 -4.70377 -0.000998899 0.000570896 0.000608526 +EDGE3 1650 1701 -4.81733 9.13804 -4.81974 -0.00663453 0.00585558 0.135355 +EDGE3 1651 1700 -4.6408 -9.13291 -4.60457 0.00378668 -0.000967019 -0.127871 +EDGE3 1652 1702 -4.15972 0.00219901 -4.69743 0.00139407 0.00473131 -0.000183465 +EDGE3 1651 1702 -4.80267 9.12288 -4.79711 0.00376719 0.00316507 0.134023 +EDGE3 1652 1701 -4.64203 -9.11309 -4.61973 -0.00141061 -0.00154033 -0.117666 +EDGE3 1653 1703 -4.18002 -0.0131363 -4.70439 -0.00620068 0.00587402 -0.00417297 +EDGE3 1652 1703 -4.83291 9.09197 -4.78353 -0.0040886 0.00456317 0.122138 +EDGE3 1653 1702 -4.67403 -9.12976 -4.60537 0.00583185 -0.00498931 -0.126544 +EDGE3 1654 1704 -4.18448 0.0132976 -4.69551 0.00131069 -0.00277018 -0.00313953 +EDGE3 1653 1704 -4.83842 9.09462 -4.80199 -0.00543834 -0.00609983 0.126431 +EDGE3 1654 1703 -4.67207 -9.09195 -4.59234 -0.00503335 0.00533246 -0.124289 +EDGE3 1655 1705 -4.17992 -0.000181804 -4.70458 -0.00508575 -0.00167492 -0.0020341 +EDGE3 1654 1705 -4.84536 9.08775 -4.78625 0.00624939 -0.000912108 0.123695 +EDGE3 1655 1704 -4.67072 -9.09434 -4.58682 -0.000277056 -0.0047591 -0.131221 +EDGE3 1656 1706 -4.1862 -0.00509544 -4.685 0.00225679 -0.001478 -0.00690749 +EDGE3 1655 1706 -4.85122 9.07741 -4.76958 0.0139134 -0.000823002 0.119473 +EDGE3 1656 1705 -4.69196 -9.09615 -4.58242 -0.00282627 0.00680526 -0.120417 +EDGE3 1657 1707 -4.20797 0.0108874 -4.69185 -0.00604935 0.00765395 0.00175865 +EDGE3 1656 1707 -4.82838 9.06632 -4.77866 -0.00183164 0.00307254 0.129021 +EDGE3 1657 1706 -4.68609 -9.07463 -4.59433 0.00563966 -4.12237e-05 -0.124394 +EDGE3 1658 1708 -4.2049 0.0131064 -4.65251 -0.000269332 0.0114614 0.0086092 +EDGE3 1657 1708 -4.84794 9.04132 -4.75838 -0.0044332 0.00215618 0.122219 +EDGE3 1658 1707 -4.67971 -9.05718 -4.57697 0.0054647 0.00328821 -0.123489 +EDGE3 1659 1709 -4.20516 0.00637796 -4.6768 0.00556877 -0.0104431 -0.004986 +EDGE3 1658 1709 -4.84662 9.0272 -4.75824 0.00106155 0.00418357 0.124685 +EDGE3 1659 1708 -4.68691 -9.04616 -4.58556 -0.000703821 0.0042345 -0.129055 +EDGE3 1660 1710 -4.22583 0.0121506 -4.6864 -0.00373211 0.0034737 -0.00128962 +EDGE3 1659 1710 -4.87416 9.00554 -4.76317 -0.000834304 0.00854185 0.123779 +EDGE3 1660 1709 -4.70051 -9.04411 -4.5719 -0.00892585 -0.000449649 -0.12711 +EDGE3 1661 1711 -4.21597 0.0010927 -4.65447 -0.00262729 -0.00402821 0.00258358 +EDGE3 1660 1711 -4.86633 9.03598 -4.75222 0.00161562 -0.00543979 0.129682 +EDGE3 1661 1710 -4.69933 -9.02764 -4.59677 -0.00333468 0.000254433 -0.115782 +EDGE3 1662 1712 -4.23964 0.0043623 -4.67167 -0.00797579 -0.000535582 -0.00292847 +EDGE3 1661 1712 -4.88432 9.00312 -4.7636 -0.0028631 -0.00501301 0.11873 +EDGE3 1662 1711 -4.68076 -9.02561 -4.57361 0.00715125 0.00460208 -0.126044 +EDGE3 1663 1713 -4.23182 -0.00279312 -4.63545 -0.0146096 0.00638409 -0.00319001 +EDGE3 1662 1713 -4.87366 8.99752 -4.73698 -0.0047047 0.00236016 0.123878 +EDGE3 1663 1712 -4.72155 -9.00038 -4.54535 0.00376695 0.00977901 -0.119774 +EDGE3 1664 1714 -4.23958 0.0129888 -4.63304 0.0118192 -0.00518014 -0.00385078 +EDGE3 1663 1714 -4.88612 8.98903 -4.72797 -0.000169648 0.00901173 0.123017 +EDGE3 1664 1713 -4.70332 -8.98331 -4.53974 -0.00452762 0.00422932 -0.133089 +EDGE3 1665 1715 -4.22799 0.014228 -4.62972 0.00462268 0.0052475 -0.000160281 +EDGE3 1664 1715 -4.88565 8.96625 -4.73948 -0.00391411 -0.000866692 0.118549 +EDGE3 1665 1714 -4.71523 -8.97752 -4.53768 0.00445796 0.00571055 -0.126613 +EDGE3 1666 1716 -4.25162 0.0303627 -4.60348 -0.00244254 0.00108424 -0.00196495 +EDGE3 1665 1716 -4.90612 8.96607 -4.70842 -0.00262567 -0.00352035 0.12487 +EDGE3 1666 1715 -4.73483 -8.99604 -4.53557 0.000389615 0.00423651 -0.12516 +EDGE3 1667 1717 -4.24388 0.00535672 -4.62765 -0.00300106 0.00495831 0.0107925 +EDGE3 1666 1717 -4.87975 8.94878 -4.72461 -0.00231821 0.000469476 0.12322 +EDGE3 1667 1716 -4.74866 -8.96251 -4.53533 0.00621168 0.00457796 -0.114136 +EDGE3 1668 1718 -4.25532 -0.01117 -4.62464 0.00257723 -0.00180109 0.00553383 +EDGE3 1667 1718 -4.89657 8.93672 -4.70703 0.00592597 0.00443951 0.120463 +EDGE3 1668 1717 -4.74483 -8.95868 -4.51209 0.00312578 0.00451317 -0.135962 +EDGE3 1669 1719 -4.26847 -0.0131743 -4.60171 -0.00957195 0.00798558 0.00366486 +EDGE3 1668 1719 -4.91704 8.93948 -4.72277 0.00191591 0.00442546 0.112895 +EDGE3 1669 1718 -4.73625 -8.92592 -4.51377 -0.00044966 0.00228388 -0.121352 +EDGE3 1670 1720 -4.25577 -0.00464193 -4.62944 -0.000295541 0.00445142 0.00158626 +EDGE3 1669 1720 -4.92452 8.92725 -4.70996 0.00309401 0.00274767 0.127608 +EDGE3 1670 1719 -4.73779 -8.92845 -4.51816 0.0118003 0.00166168 -0.128596 +EDGE3 1671 1721 -4.28675 0.00149759 -4.60476 0.00319138 -0.00248812 -0.0125123 +EDGE3 1670 1721 -4.92671 8.9114 -4.6809 -0.00275952 0.000759767 0.129683 +EDGE3 1671 1720 -4.74808 -8.92176 -4.50678 0.00468118 0.000544573 -0.1248 +EDGE3 1672 1722 -4.29078 0.034295 -4.59209 -0.00308602 -0.00251812 -0.00979769 +EDGE3 1671 1722 -4.93283 8.88489 -4.70748 -0.00326472 -0.00469712 0.126926 +EDGE3 1672 1721 -4.77834 -8.90881 -4.50584 -0.00107413 -0.00381126 -0.114999 +EDGE3 1673 1723 -4.28242 0.00358281 -4.60462 0.00964151 0.00163484 -0.00362938 +EDGE3 1672 1723 -4.92148 8.89134 -4.68452 0.000375302 -0.00826138 0.130107 +EDGE3 1673 1722 -4.76792 -8.90306 -4.50061 0.00697895 -0.000421179 -0.125653 +EDGE3 1674 1724 -4.30052 0.00633884 -4.58515 -0.00253353 -0.00529516 -0.00127023 +EDGE3 1673 1724 -4.94464 8.86059 -4.67694 -0.000544734 -0.00258342 0.129776 +EDGE3 1674 1723 -4.76358 -8.86808 -4.49177 -0.00418489 -0.0141504 -0.127068 +EDGE3 1675 1725 -4.31165 -0.00818276 -4.58452 -0.009971 0.00886481 -0.00566623 +EDGE3 1674 1725 -4.93586 8.86321 -4.68176 -0.00422354 0.00377783 0.132577 +EDGE3 1675 1724 -4.76953 -8.87286 -4.49305 -0.00167775 0.000331235 -0.124678 +EDGE3 1676 1726 -4.31164 0.00571919 -4.58667 -0.00468263 -0.00194978 -0.00132212 +EDGE3 1675 1726 -4.93997 8.84437 -4.65261 -0.000167786 0.000104181 0.129931 +EDGE3 1676 1725 -4.77941 -8.87638 -4.49565 -0.000187769 0.00330084 -0.129126 +EDGE3 1677 1727 -4.31403 -0.0196701 -4.55716 0.0061161 -0.00555722 -0.00629173 +EDGE3 1676 1727 -4.95711 8.85579 -4.65892 -0.000919771 -0.00256334 0.127485 +EDGE3 1677 1726 -4.78228 -8.83845 -4.47707 -0.00109133 0.00110206 -0.121473 +EDGE3 1678 1728 -4.33794 -0.0164352 -4.55956 0.00429431 0.000165962 0.000884389 +EDGE3 1677 1728 -4.95661 8.82869 -4.66072 -0.00316723 0.00793386 0.124531 +EDGE3 1678 1727 -4.77785 -8.83718 -4.48595 0.00350964 0.00568172 -0.116865 +EDGE3 1679 1729 -4.31525 0.00269397 -4.55793 0.00878647 -0.00260927 -0.00383216 +EDGE3 1678 1729 -4.97346 8.83017 -4.64623 -0.00274325 -0.00307444 0.123099 +EDGE3 1679 1728 -4.786 -8.83604 -4.46671 -0.00547425 0.00542749 -0.119632 +EDGE3 1680 1730 -4.31761 0.00329516 -4.54566 0.0022042 0.000149604 0.00284097 +EDGE3 1679 1730 -4.98487 8.81945 -4.64855 0.0033144 -0.00875135 0.118714 +EDGE3 1680 1729 -4.78459 -8.81559 -4.46759 -0.00362935 -0.00184716 -0.127951 +EDGE3 1681 1731 -4.30718 0.0110936 -4.53561 0.00618073 0.0114344 -0.00232646 +EDGE3 1680 1731 -4.97796 8.78243 -4.63355 -2.14804e-05 0.00101139 0.132182 +EDGE3 1681 1730 -4.79784 -8.79698 -4.45292 -0.00452767 -0.00172435 -0.129451 +EDGE3 1682 1732 -4.3441 0.0028258 -4.54216 0.00260455 -0.00139087 0.00324802 +EDGE3 1681 1732 -4.9637 8.78635 -4.64448 -0.000174962 0.000292578 0.121342 +EDGE3 1682 1731 -4.81898 -8.80072 -4.45261 -0.00774525 -0.00684096 -0.130918 +EDGE3 1683 1733 -4.36169 -0.0158012 -4.54956 0.00387508 -0.00324181 -0.00247696 +EDGE3 1682 1733 -4.99428 8.77174 -4.6237 0.000477345 -0.00312958 0.117479 +EDGE3 1683 1732 -4.80569 -8.79585 -4.44888 0.000332706 -0.000897391 -0.126135 +EDGE3 1684 1734 -4.34099 0.00334482 -4.51972 0.000634945 0.00428358 0.00194475 +EDGE3 1684 1733 -4.82911 -8.76615 -4.4539 0.00273921 0.00138702 -0.126018 +EDGE3 1683 1734 -4.96002 8.78092 -4.64583 -0.00367001 0.00491469 0.128257 +EDGE3 1685 1735 -4.37173 -0.00410781 -4.53219 0.00418089 -0.00517842 0.00800469 +EDGE3 1684 1735 -4.9854 8.74392 -4.62322 0.000220235 0.00161138 0.119275 +EDGE3 1685 1734 -4.81719 -8.77033 -4.439 -0.0132083 -0.00706605 -0.123331 +EDGE3 1686 1736 -4.36942 -0.00402917 -4.52238 -0.0078227 -0.00206147 -0.0100731 +EDGE3 1685 1736 -5.0087 8.73428 -4.60452 -0.000282408 0.000724935 0.127412 +EDGE3 1686 1735 -4.80288 -8.73756 -4.41935 0.00381148 -0.00106239 -0.122515 +EDGE3 1687 1737 -4.36181 -0.00474635 -4.5243 0.000909483 -0.00154803 -0.000787887 +EDGE3 1686 1737 -5.01934 8.73331 -4.58611 -0.00307529 -0.000810487 0.134361 +EDGE3 1687 1736 -4.81253 -8.75108 -4.43653 -0.00153382 -0.00520643 -0.126604 +EDGE3 1688 1738 -4.38224 -0.00540633 -4.51198 0.00146375 -0.0106065 0.00305451 +EDGE3 1687 1738 -4.99891 8.7338 -4.58859 0.00298285 -0.00371002 0.127447 +EDGE3 1688 1737 -4.83451 -8.73604 -4.39548 0.00113792 0.00621816 -0.12314 +EDGE3 1689 1739 -4.39038 -0.0105854 -4.49713 -0.00131952 0.000131335 -0.00836743 +EDGE3 1688 1739 -5.01803 8.69484 -4.60688 0.0119291 0.00210997 0.127987 +EDGE3 1689 1738 -4.85527 -8.70447 -4.40592 0.00317344 -0.00593 -0.117514 +EDGE3 1690 1740 -4.36903 -0.0104012 -4.48739 0.00449158 -0.00451986 0.00648512 +EDGE3 1689 1740 -5.0075 8.69523 -4.58242 -0.00279991 0.0106408 0.137933 +EDGE3 1690 1739 -4.84747 -8.72002 -4.4058 0.000496247 0.00589708 -0.134672 +EDGE3 1691 1741 -4.39304 0.00692134 -4.5144 -0.00220463 0.0047561 -0.00138436 +EDGE3 1690 1741 -5.01704 8.68603 -4.56287 0.000847744 0.00253885 0.130202 +EDGE3 1691 1740 -4.84184 -8.70628 -4.41416 0.00562336 -0.00578378 -0.13296 +EDGE3 1692 1742 -4.38897 -0.00449661 -4.49035 0.00194257 -0.00160933 -0.00432162 +EDGE3 1691 1742 -5.03774 8.6796 -4.58548 0.000363956 -0.00486728 0.13187 +EDGE3 1692 1741 -4.84886 -8.69545 -4.40172 0.0025894 0.00295973 -0.115509 +EDGE3 1693 1743 -4.40708 -0.00569221 -4.47399 -0.00498746 0.00867546 0.00137393 +EDGE3 1692 1743 -5.04349 8.65785 -4.56907 -0.00291 0.010603 0.122057 +EDGE3 1693 1742 -4.8405 -8.66571 -4.38482 0.00135854 -0.00676043 -0.133042 +EDGE3 1694 1744 -4.4007 0.00994336 -4.48445 7.34832e-05 -0.00333746 -0.000702462 +EDGE3 1693 1744 -5.04762 8.65222 -4.56543 -0.0042012 -0.00844482 0.129686 +EDGE3 1694 1743 -4.8656 -8.66024 -4.38358 0.00085912 0.003008 -0.120074 +EDGE3 1695 1745 -4.41362 0.01294 -4.47275 -0.0038264 -0.00024204 0.00258891 +EDGE3 1694 1745 -5.0473 8.64208 -4.56154 -0.00551352 -0.0003898 0.126555 +EDGE3 1695 1744 -4.86789 -8.63062 -4.38368 0.0086523 0.00216079 -0.12185 +EDGE3 1696 1746 -4.41311 0.00214969 -4.45357 0.00159766 0.00311548 0.00226148 +EDGE3 1695 1746 -5.04746 8.62293 -4.55023 -0.00563831 0.00265312 0.119654 +EDGE3 1696 1745 -4.87957 -8.63516 -4.39027 -0.00962347 0.00130697 -0.120536 +EDGE3 1697 1747 -4.41503 0.00210496 -4.45573 0.00538025 -0.00128407 0.00668189 +EDGE3 1696 1747 -5.04101 8.62213 -4.56043 -0.00548079 0.000793909 0.125671 +EDGE3 1697 1746 -4.86441 -8.62412 -4.38519 -0.00289274 -0.00540686 -0.12782 +EDGE3 1698 1748 -4.42465 -0.00464751 -4.45985 -0.00276308 -0.00242226 -0.00663108 +EDGE3 1697 1748 -5.06591 8.6006 -4.52984 0.00335108 0.00113404 0.123171 +EDGE3 1698 1747 -4.87444 -8.60123 -4.38706 -0.00575098 -0.00337009 -0.133128 +EDGE3 1699 1749 -4.44371 -0.0113162 -4.43441 0.00809028 0.00498031 -0.0102428 +EDGE3 1698 1749 -5.07667 8.59351 -4.52404 -8.5728e-05 0.00350579 0.120422 +EDGE3 1700 1750 -4.45236 -0.00705054 -4.45754 -0.00378332 -0.00257898 0.00298916 +EDGE3 1699 1748 -4.89652 -8.61237 -4.37625 0.0129591 -0.00528218 -0.130018 +EDGE3 1699 1750 -5.04271 8.56347 -4.53598 0.003471 0.000423868 0.126308 +EDGE3 1700 1749 -4.87578 -8.59505 -4.37015 0.00935253 -0.00168296 -0.126936 +EDGE3 1701 1751 -4.46049 0.00798648 -4.45272 0.000370422 0.00267349 -0.00102382 +EDGE3 1700 1751 -5.06907 8.55351 -4.5381 0.00139123 0.0102243 0.123226 +EDGE3 1701 1750 -4.8992 -8.57448 -4.33835 0.0054555 0.00123458 -0.125788 +EDGE3 1702 1752 -4.44518 0.00323281 -4.43382 0.000826114 0.00230521 -0.000113086 +EDGE3 1701 1752 -5.07626 8.56471 -4.53058 0.00375864 0.00570348 0.128089 +EDGE3 1702 1751 -4.89665 -8.58507 -4.34155 -0.00217607 -0.00199205 -0.130974 +EDGE3 1703 1753 -4.4651 0.00939533 -4.42706 0.00350832 -0.00326822 -0.000364994 +EDGE3 1702 1753 -5.09335 8.56292 -4.52117 -0.000707714 -0.00861237 0.1291 +EDGE3 1703 1752 -4.899 -8.55566 -4.35445 0.000345189 -0.00591062 -0.125339 +EDGE3 1704 1754 -4.4497 0.00952033 -4.40723 -0.00136015 0.00483003 -0.00634331 +EDGE3 1703 1754 -5.08801 8.54132 -4.52116 0.00547432 -0.00332294 0.119197 +EDGE3 1704 1753 -4.92135 -8.54605 -4.34635 -0.00303679 0.00604921 -0.123965 +EDGE3 1705 1755 -4.45946 0.015731 -4.40319 0.000284728 -0.00592529 -0.00108802 +EDGE3 1704 1755 -5.07976 8.53654 -4.51348 0.000484851 -0.00159348 0.127008 +EDGE3 1705 1754 -4.90088 -8.53865 -4.31705 0.0088525 -0.00500423 -0.119701 +EDGE3 1706 1756 -4.46257 0.000926902 -4.40259 0.00573307 -0.00432296 -0.00555538 +EDGE3 1705 1756 -5.09243 8.52211 -4.49712 0.00406685 -0.0013744 0.12301 +EDGE3 1706 1755 -4.90005 -8.52429 -4.32648 0.00635644 -0.00675784 -0.121464 +EDGE3 1707 1757 -4.46848 0.00521947 -4.39639 0.00729026 -0.00088031 -0.00354317 +EDGE3 1706 1757 -5.09578 8.51391 -4.48832 0.0120641 0.0053398 0.132208 +EDGE3 1707 1756 -4.9173 -8.50643 -4.32755 0.00060621 -0.00779663 -0.126749 +EDGE3 1708 1758 -4.484 0.00899231 -4.40492 0.000799994 -0.0127595 0.000709404 +EDGE3 1707 1758 -5.0975 8.48278 -4.47668 0.0042559 -0.00349921 0.126635 +EDGE3 1708 1757 -4.92552 -8.50945 -4.32066 -0.000143342 -0.00113564 -0.132282 +EDGE3 1709 1759 -4.48968 0.0115846 -4.39342 -0.00164469 -0.00168715 0.000217034 +EDGE3 1708 1759 -5.10807 8.46415 -4.47587 -0.00192864 -0.00736527 0.120389 +EDGE3 1710 1760 -4.49283 0.0125112 -4.38815 0.00705472 0.00380897 -0.0037911 +EDGE3 1709 1758 -4.92315 -8.5013 -4.29363 0.00114813 -0.00283735 -0.121849 +EDGE3 1710 1759 -4.93509 -8.47433 -4.31526 0.00440049 -0.00479369 -0.120341 +EDGE3 1709 1760 -5.12883 8.46256 -4.47495 -0.00138098 -0.000103337 0.108133 +EDGE3 1710 1761 -5.1234 8.46638 -4.48053 -0.00123546 0.00885002 0.127603 +EDGE3 1711 1761 -4.49792 0.00311464 -4.3748 0.00341599 0.00660777 0.0125708 +EDGE3 1712 1762 -4.50237 -0.0160664 -4.36593 -0.00428098 0.00392426 0.00125971 +EDGE3 1711 1760 -4.94714 -8.46614 -4.29401 -0.00270889 -0.00519733 -0.124156 +EDGE3 1711 1762 -5.14711 8.43539 -4.47478 0.00136092 0.001311 0.126453 +EDGE3 1712 1761 -4.94556 -8.46075 -4.30707 0.000246495 0.00531703 -0.129555 +EDGE3 1713 1763 -4.51304 0.00697735 -4.3694 -0.0045643 -0.00260599 0.00446324 +EDGE3 1712 1763 -5.13318 8.4318 -4.46652 -0.00739496 0.00686113 0.122909 +EDGE3 1713 1762 -4.96531 -8.44798 -4.27752 -0.0038679 -0.00763536 -0.112975 +EDGE3 1714 1764 -4.51276 0.00308011 -4.35993 0.00416367 -0.00676518 -0.00111717 +EDGE3 1713 1764 -5.13018 8.41767 -4.45857 -0.00577241 -0.000868907 0.129002 +EDGE3 1714 1763 -4.97333 -8.42611 -4.27234 -0.00351826 0.00350512 -0.125859 +EDGE3 1715 1765 -4.53176 0.00413484 -4.34819 0.000817555 0.00186237 0.00165233 +EDGE3 1714 1765 -5.13922 8.39717 -4.4455 -0.00278324 0.00157898 0.117229 +EDGE3 1715 1764 -4.95969 -8.43194 -4.26933 -0.00151073 0.0123417 -0.120022 +EDGE3 1716 1766 -4.52251 0.0149422 -4.33271 0.000936408 0.00316246 0.00514966 +EDGE3 1715 1766 -5.14581 8.3821 -4.4375 0.00423475 0.000172169 0.125834 +EDGE3 1716 1765 -4.94955 -8.40509 -4.24594 -0.00567556 0.000627613 -0.126141 +EDGE3 1717 1767 -4.54202 0.00218461 -4.35846 -0.000606305 0.00768407 -0.00626311 +EDGE3 1716 1767 -5.16477 8.38548 -4.42922 0.00329349 0.00296248 0.123987 +EDGE3 1717 1766 -4.96868 -8.3877 -4.25713 -0.000186241 0.000111906 -0.13634 +EDGE3 1718 1768 -4.54136 0.0107697 -4.33926 0.00442219 -0.00220691 -0.00542465 +EDGE3 1717 1768 -5.16616 8.37161 -4.43332 -0.0114601 0.00761787 0.122307 +EDGE3 1718 1767 -4.96573 -8.37623 -4.23402 0.00309118 -0.00311486 -0.123504 +EDGE3 1719 1769 -4.53433 -0.00975262 -4.32641 -0.0070963 0.0022297 -0.00195741 +EDGE3 1718 1769 -5.1447 8.37326 -4.41194 0.00827199 -0.00413407 0.121609 +EDGE3 1719 1768 -4.99136 -8.36359 -4.26033 0.00867431 -0.00678133 -0.116108 +EDGE3 1720 1770 -4.55678 0.00171422 -4.31729 0.00138441 0.00012597 -0.00697187 +EDGE3 1719 1770 -5.16885 8.37194 -4.43036 0.00342476 0.00450472 0.128717 +EDGE3 1720 1769 -4.98139 -8.36608 -4.24723 0.00750154 -0.00449769 -0.122945 +EDGE3 1721 1771 -4.57164 0.0113314 -4.32356 -0.0040172 0.000747102 0.00468946 +EDGE3 1720 1771 -5.16851 8.32499 -4.40891 0.00178716 0.0023435 0.120161 +EDGE3 1721 1770 -5.00596 -8.33411 -4.22408 0.00926322 -0.00925389 -0.124937 +EDGE3 1721 1772 -5.16199 8.31172 -4.40662 0.000669806 -0.00175479 0.118003 +EDGE3 1722 1772 -4.56776 0.010436 -4.30607 -0.00290992 -0.00349028 0.0145956 +EDGE3 1723 1773 -4.54749 -0.00575548 -4.30011 -0.00272673 -0.00463424 -0.00632915 +EDGE3 1722 1771 -5.00931 -8.32701 -4.23034 -0.00100431 -0.00163772 -0.12069 +EDGE3 1722 1773 -5.19127 8.30533 -4.38992 -0.00153109 0.00237621 0.1232 +EDGE3 1723 1772 -4.99892 -8.33374 -4.24594 0.000498813 0.00528544 -0.134092 +EDGE3 1723 1774 -5.191 8.30273 -4.38961 -0.00434474 0.00303882 0.130567 +EDGE3 1724 1774 -4.55253 0.0114572 -4.3 0.000762637 0.00849202 0.00157689 +EDGE3 1725 1775 -4.59058 0.0197414 -4.29032 -0.0059671 0.0054069 -0.00562307 +EDGE3 1724 1773 -5.00745 -8.30539 -4.22362 -0.00745695 0.000972062 -0.119974 +EDGE3 1725 1774 -4.99439 -8.31173 -4.23116 -0.0103693 0.0021548 -0.12505 +EDGE3 1724 1775 -5.19737 8.28331 -4.38252 -0.0104314 0.00174383 0.122321 +EDGE3 1726 1776 -4.59495 0.0020752 -4.26758 0.00248563 -0.000526836 0.00723026 +EDGE3 1725 1776 -5.20232 8.28554 -4.36899 0.00523754 0.00329576 0.12395 +EDGE3 1726 1775 -5.00208 -8.28338 -4.20231 -0.00608037 0.00731839 -0.125097 +EDGE3 1727 1777 -4.58787 -0.0205211 -4.29688 -0.00101479 -0.00142098 0.000464129 +EDGE3 1726 1777 -5.19432 8.27393 -4.3709 -0.00451765 -0.00295319 0.125067 +EDGE3 1727 1776 -5.02707 -8.28532 -4.20844 -0.00284807 0.00955394 -0.120821 +EDGE3 1728 1778 -4.6086 -0.00711997 -4.29425 0.00331387 -0.00301041 -0.000453984 +EDGE3 1727 1778 -5.20365 8.24888 -4.36058 0.00406661 0.00867243 0.125156 +EDGE3 1728 1777 -5.02273 -8.2479 -4.17873 0.00400238 -0.00235402 -0.121914 +EDGE3 1729 1779 -4.63008 0.00812799 -4.27792 0.00160863 0.010225 -0.00725794 +EDGE3 1728 1779 -5.20525 8.26706 -4.34811 -0.002964 0.00736525 0.121271 +EDGE3 1729 1778 -5.02845 -8.24873 -4.19639 -0.00178973 -0.00647615 -0.131851 +EDGE3 1730 1780 -4.60187 0.000342963 -4.25134 -0.000381185 -0.00428038 0.00309793 +EDGE3 1729 1780 -5.20199 8.23186 -4.36814 -0.00823378 -0.00931865 0.128425 +EDGE3 1730 1779 -5.04228 -8.25032 -4.1859 0.00369481 0.00110395 -0.139163 +EDGE3 1731 1781 -4.60835 0.00191288 -4.26341 -0.00339761 0.00830836 0.000769442 +EDGE3 1730 1781 -5.2157 8.22484 -4.3712 0.00266939 -0.00217112 0.129647 +EDGE3 1731 1780 -5.03398 -8.2375 -4.19463 -0.0040721 -0.00166024 -0.130632 +EDGE3 1732 1782 -4.63037 0.00848965 -4.274 -0.00267054 0.0103415 0.00452662 +EDGE3 1731 1782 -5.22795 8.21063 -4.35978 0.000566959 -0.0083883 0.123631 +EDGE3 1732 1781 -5.03891 -8.2299 -4.16868 0.00065623 0.00232714 -0.130674 +EDGE3 1733 1783 -4.60016 -0.00860163 -4.25183 0.00478151 0.00117961 -0.00530487 +EDGE3 1732 1783 -5.23925 8.18871 -4.33956 0.0037349 -0.000634506 0.127712 +EDGE3 1733 1782 -5.04457 -8.19967 -4.15586 0.00421057 -0.00355809 -0.123458 +EDGE3 1734 1784 -4.62424 0.00677294 -4.24528 0.00200275 -0.000736637 0.00552751 +EDGE3 1733 1784 -5.22954 8.17159 -4.33968 -0.00295495 0.00460209 0.128511 +EDGE3 1734 1783 -5.05135 -8.20596 -4.15307 -0.000414325 -0.00168699 -0.131907 +EDGE3 1735 1785 -4.64245 0.021599 -4.23255 0.0127402 0.00594648 0.00381897 +EDGE3 1734 1785 -5.23487 8.1664 -4.33964 -0.0026474 -0.00199457 0.11777 +EDGE3 1735 1784 -5.06288 -8.19665 -4.16899 0.0078167 -0.00231779 -0.125445 +EDGE3 1736 1786 -4.62573 -0.014816 -4.2376 0.00366719 0.00154659 0.00599622 +EDGE3 1735 1786 -5.24302 8.15977 -4.32778 -0.00230045 0.00228577 0.123411 +EDGE3 1736 1785 -5.06076 -8.16643 -4.15056 0.00209257 0.00284555 -0.120358 +EDGE3 1737 1787 -4.62882 0.0146314 -4.21451 -0.00321084 0.00268585 -0.00388649 +EDGE3 1736 1787 -5.23814 8.13953 -4.3182 -0.00406714 0.00449396 0.128993 +EDGE3 1737 1786 -5.06797 -8.14391 -4.14988 0.00726148 -0.00311446 -0.121721 +EDGE3 1738 1788 -4.65693 -0.00346666 -4.2304 0.00584184 -0.00113563 -0.00302043 +EDGE3 1737 1788 -5.23424 8.12263 -4.30278 -0.00899633 -0.00147957 0.133166 +EDGE3 1738 1787 -5.06358 -8.14854 -4.14025 0.00595407 -0.00505718 -0.123507 +EDGE3 1739 1789 -4.64807 0.0141632 -4.22369 -0.0046028 0.00157621 -0.00518617 +EDGE3 1738 1789 -5.25673 8.13908 -4.31067 0.00443065 -0.0076489 0.133201 +EDGE3 1739 1788 -5.05153 -8.13869 -4.14819 0.00587418 0.000365209 -0.127118 +EDGE3 1740 1790 -4.65897 -0.0251027 -4.19734 0.00486756 -0.00282808 -0.00942836 +EDGE3 1739 1790 -5.26869 8.11189 -4.30704 0.00306314 -0.00973383 0.128872 +EDGE3 1740 1789 -5.08049 -8.11853 -4.13949 -0.00620491 -0.00229984 -0.127662 +EDGE3 1741 1791 -4.68684 -0.0130904 -4.21135 0.00489631 0.00226499 -0.000752785 +EDGE3 1740 1791 -5.27284 8.10051 -4.28521 -0.00286927 0.00720689 0.125303 +EDGE3 1741 1790 -5.07229 -8.11171 -4.13528 0.00604315 0.00806346 -0.121215 +EDGE3 1742 1792 -4.67802 0.00904448 -4.20022 -0.00331855 0.00623112 9.3183e-05 +EDGE3 1741 1792 -5.26671 8.08479 -4.27136 -0.000728376 0.00209457 0.128439 +EDGE3 1742 1791 -5.09315 -8.09908 -4.13417 0.000512083 0.00137468 -0.12285 +EDGE3 1743 1793 -4.66871 -0.00416177 -4.19493 -0.00122527 -0.00411521 0.00477443 +EDGE3 1742 1793 -5.25271 8.05949 -4.28504 -0.000997616 0.00292075 0.12906 +EDGE3 1743 1792 -5.08728 -8.10157 -4.11796 -0.00352996 0.0112946 -0.128655 +EDGE3 1744 1794 -4.67607 -0.0164956 -4.20775 -0.0010249 -0.00241265 -0.000756646 +EDGE3 1743 1794 -5.27185 8.05985 -4.28165 0.000365503 0.00337678 0.121361 +EDGE3 1744 1793 -5.07705 -8.07913 -4.11719 -0.00196629 0.00487034 -0.116681 +EDGE3 1745 1795 -4.69014 0.00689332 -4.17939 0.0013063 0.00501747 0.00589266 +EDGE3 1744 1795 -5.28611 8.04939 -4.27355 -0.00738489 0.00231815 0.123287 +EDGE3 1745 1794 -5.1018 -8.04551 -4.09743 -0.000560897 0.0046368 -0.132156 +EDGE3 1746 1796 -4.67279 -0.010781 -4.17909 -0.00402326 0.000453071 0.00120132 +EDGE3 1745 1796 -5.29535 8.04627 -4.25475 0.00144265 -0.000521883 0.120663 +EDGE3 1746 1795 -5.10249 -8.0536 -4.09243 0.0106755 0.00122832 -0.123796 +EDGE3 1747 1797 -4.6757 -0.00520637 -4.17606 0.000429574 -0.00245913 0.00416866 +EDGE3 1746 1797 -5.28419 8.02783 -4.2623 0.00463312 0.00782927 0.123273 +EDGE3 1747 1796 -5.09406 -8.0498 -4.10425 -0.00187039 0.00416645 -0.134958 +EDGE3 1748 1798 -4.71018 -0.00698221 -4.17471 -0.00258531 -0.00272227 -0.00507046 +EDGE3 1747 1798 -5.29158 8.01249 -4.2505 0.00201218 0.000138243 0.126248 +EDGE3 1748 1797 -5.12016 -8.01475 -4.08016 0.00049422 -0.00760895 -0.131083 +EDGE3 1749 1799 -4.68782 -0.0111991 -4.16818 -0.00226408 0.00574161 -0.00305846 +EDGE3 1748 1799 -5.29437 7.99409 -4.26855 0.0118761 -0.00293562 0.122421 +EDGE3 1749 1798 -5.10801 -8.0097 -4.08845 -0.00314819 -0.00526993 -0.124368 +EDGE3 1750 1800 -4.72621 0.00537238 -4.16265 -0.00318734 -0.00772941 -0.00151341 +EDGE3 1749 1800 -5.30981 7.985 -4.24272 -0.00391773 0.000450729 0.113754 +EDGE3 1750 1799 -5.13644 -7.98805 -4.08241 0.00932772 -0.00387961 -0.122076 +EDGE3 1751 1801 -4.70324 0.0138451 -4.15651 0.00166608 -0.00265305 -0.00290447 +EDGE3 1750 1801 -5.32069 7.98418 -4.23031 -0.00679922 0.00964936 0.117496 +EDGE3 1751 1800 -5.13139 -7.98015 -4.06904 0.00172066 -0.00836222 -0.130198 +EDGE3 1752 1802 -4.72115 0.0139493 -4.13187 -0.0014766 -0.014939 0.00168664 +EDGE3 1751 1802 -5.30548 7.95819 -4.23849 0.00611377 0.0028769 0.123041 +EDGE3 1752 1801 -5.11693 -7.97313 -4.05684 -0.00354816 -0.00410488 -0.119149 +EDGE3 1753 1803 -4.72733 -0.00365942 -4.13047 -0.00118614 -0.00406997 -0.0045082 +EDGE3 1752 1803 -5.31584 7.97011 -4.21404 -0.0107719 0.000955658 0.124064 +EDGE3 1753 1802 -5.13727 -7.95391 -4.04357 -0.00636282 0.00605131 -0.127976 +EDGE3 1754 1804 -4.73303 0.00824849 -4.14055 0.00320722 0.00567422 0.00613668 +EDGE3 1753 1804 -5.35771 7.92837 -4.2063 -0.000499519 -0.00438431 0.117675 +EDGE3 1754 1803 -5.1216 -7.96829 -4.05894 -0.000195688 -0.00975751 -0.127977 +EDGE3 1755 1805 -4.73812 -0.00115125 -4.11209 0.00549137 0.0016974 -0.00327842 +EDGE3 1754 1805 -5.32593 7.94897 -4.20147 0.00217093 -0.00490961 0.124266 +EDGE3 1755 1804 -5.14246 -7.951 -4.03964 -7.39711e-05 -0.0101504 -0.135882 +EDGE3 1756 1806 -4.73491 0.00554777 -4.12654 -0.00384748 -0.00756305 0.000936419 +EDGE3 1755 1806 -5.34869 7.91676 -4.20212 0.000942932 0.010556 0.128113 +EDGE3 1756 1805 -5.1391 -7.92164 -4.03041 0.000111205 0.000860223 -0.124374 +EDGE3 1757 1807 -4.73603 0.0137769 -4.1044 0.00101579 0.000533995 0.00486616 +EDGE3 1756 1807 -5.34331 7.88522 -4.19032 0.00177316 0.000687699 0.126979 +EDGE3 1757 1806 -5.15927 -7.92953 -4.03785 0.00120464 0.00362688 -0.131577 +EDGE3 1758 1808 -4.74915 0.0191835 -4.11207 0.00219347 -0.00219849 0.000813812 +EDGE3 1757 1808 -5.35028 7.88986 -4.19937 -0.00869138 -0.000909058 0.126577 +EDGE3 1758 1807 -5.15579 -7.90556 -4.02166 0.00465166 -0.00692597 -0.114966 +EDGE3 1759 1809 -4.74784 0.00746766 -4.09928 -0.00426062 0.011699 0.00576415 +EDGE3 1758 1809 -5.34219 7.89653 -4.19038 -0.00159798 -0.00228124 0.13112 +EDGE3 1759 1808 -5.16525 -7.90268 -4.01151 0.0010245 0.00525392 -0.133086 +EDGE3 1760 1810 -4.7538 0.00135746 -4.08172 -0.0070659 0.00461226 -0.000580874 +EDGE3 1759 1810 -5.34691 7.85419 -4.19329 -0.00367259 -0.00147655 0.128614 +EDGE3 1760 1809 -5.1418 -7.87608 -4.02225 0.00622532 -0.00134709 -0.133488 +EDGE3 1761 1811 -4.77255 -0.00110079 -4.0811 -0.00262756 -0.000165943 -0.00103222 +EDGE3 1760 1811 -5.34284 7.85372 -4.17837 -0.00564045 -0.0113174 0.133062 +EDGE3 1761 1810 -5.1708 -7.87224 -4.0076 0.00850324 -0.00265002 -0.124141 +EDGE3 1762 1812 -4.77692 -0.00569195 -4.09551 0.00363279 -0.00449926 0.00371681 +EDGE3 1761 1812 -5.34746 7.8393 -4.16966 0.00560402 -0.00162355 0.12054 +EDGE3 1762 1811 -5.17281 -7.85174 -4.01088 -0.00657454 0.00256248 -0.122076 +EDGE3 1763 1813 -4.80013 0.0084665 -4.09251 -0.000928648 -0.00437505 0.00119567 +EDGE3 1762 1813 -5.3615 7.82854 -4.17036 0.00455725 -0.0088188 0.121235 +EDGE3 1763 1812 -5.17578 -7.84989 -3.99364 -0.00471841 -0.00278453 -0.115941 +EDGE3 1764 1814 -4.7965 -0.00856955 -4.09089 -0.00397412 -0.00765278 0.00385453 +EDGE3 1763 1814 -5.38853 7.83431 -4.14929 -0.00045628 0.00353677 0.13121 +EDGE3 1764 1813 -5.19144 -7.83442 -3.99254 0.00352233 0.00603581 -0.118649 +EDGE3 1765 1815 -4.79206 0.00558584 -4.04563 0.00871251 -0.0042922 0.00309926 +EDGE3 1764 1815 -5.36725 7.81201 -4.15596 0.0111923 -0.00197418 0.115448 +EDGE3 1765 1814 -5.19035 -7.82217 -3.99147 0.00512521 -0.00460267 -0.128611 +EDGE3 1766 1816 -4.77845 -0.00441256 -4.0442 -0.00704164 -8.95846e-05 -0.00185803 +EDGE3 1765 1816 -5.37342 7.79742 -4.13513 -0.00552393 -0.00161662 0.124233 +EDGE3 1766 1815 -5.18121 -7.82633 -3.98698 0.00629875 -0.00856354 -0.120885 +EDGE3 1767 1817 -4.79596 -0.000962819 -4.05806 0.00413666 -0.00349824 -0.00192466 +EDGE3 1766 1817 -5.37867 7.77698 -4.13265 0.0041633 0.00647043 0.126957 +EDGE3 1767 1816 -5.18916 -7.79138 -3.98298 0.00663967 0.00766212 -0.12802 +EDGE3 1768 1818 -4.80544 0.0209846 -4.03808 -0.00441055 0.00844551 0.00481835 +EDGE3 1767 1818 -5.4133 7.76554 -4.12357 -0.00175648 -0.00383894 0.123008 +EDGE3 1768 1817 -5.19664 -7.78826 -3.97123 -0.000770452 0.00700671 -0.128765 +EDGE3 1769 1819 -4.81074 -0.00558745 -4.0382 -0.00148769 0.00269292 -0.00495283 +EDGE3 1768 1819 -5.39598 7.73728 -4.11962 0.00664756 0.00162131 0.137232 +EDGE3 1769 1818 -5.21689 -7.78695 -3.97569 0.000504212 -0.00505802 -0.119798 +EDGE3 1770 1820 -4.79754 -0.0108635 -4.04929 -0.000970622 0.011511 0.000467437 +EDGE3 1769 1820 -5.39582 7.74739 -4.13121 -0.00304358 2.85913e-05 0.129226 +EDGE3 1770 1819 -5.21457 -7.76097 -3.96217 -0.00130464 -0.0064372 -0.124357 +EDGE3 1771 1821 -4.81698 0.00055318 -4.02664 -0.00606606 -0.00974667 0.00453535 +EDGE3 1770 1821 -5.3956 7.7497 -4.11525 -0.00229933 -0.00115196 0.127435 +EDGE3 1771 1820 -5.21844 -7.75128 -3.95358 -0.00289642 -0.00191802 -0.125668 +EDGE3 1772 1822 -4.83576 0.00933636 -4.01842 -0.00413467 -0.0025674 0.00329193 +EDGE3 1771 1822 -5.40122 7.69734 -4.09303 0.000561841 0.0122773 0.125269 +EDGE3 1772 1821 -5.21745 -7.73242 -3.94373 0.0127426 0.00271038 -0.116791 +EDGE3 1773 1823 -4.82507 -0.00601204 -4.01117 -0.00208013 -0.00446983 0.0013009 +EDGE3 1772 1823 -5.42028 7.7075 -4.10698 -0.00932063 0.000346995 0.124843 +EDGE3 1773 1822 -5.20739 -7.71818 -3.93356 0.00738314 -0.00595838 -0.130112 +EDGE3 1774 1824 -4.82984 -0.00337805 -4.00393 0.00258337 0.000199836 -0.00649597 +EDGE3 1773 1824 -5.40638 7.7115 -4.09022 -0.00219855 -0.00791974 0.119325 +EDGE3 1774 1823 -5.21905 -7.68666 -3.9526 0.00558806 -0.00767765 -0.127598 +EDGE3 1775 1825 -4.83274 -0.00111258 -4.0168 0.000991733 -0.00217823 -0.00313342 +EDGE3 1774 1825 -5.41707 7.69115 -4.07404 -0.000334088 -0.00265889 0.124718 +EDGE3 1775 1824 -5.22695 -7.69678 -3.92552 -0.00166643 -0.00179389 -0.127163 +EDGE3 1776 1826 -4.84101 -0.00161329 -4.01365 -0.000490922 0.00654347 -0.00504623 +EDGE3 1775 1826 -5.41879 7.67467 -4.08883 0.00242679 -0.00406071 0.121281 +EDGE3 1776 1825 -5.22249 -7.68455 -3.92203 -0.0020291 -0.00151756 -0.121786 +EDGE3 1777 1827 -4.84104 0.0141983 -3.99493 0.00309375 0.00137081 -0.00949915 +EDGE3 1776 1827 -5.43444 7.64723 -4.06912 -0.00647614 -0.00409586 0.12987 +EDGE3 1777 1826 -5.2299 -7.66891 -3.92358 0.00713252 0.0119419 -0.121868 +EDGE3 1778 1828 -4.86067 0.0100221 -3.98931 -0.000287284 -0.00724482 0.00268864 +EDGE3 1777 1828 -5.43804 7.63237 -4.06572 0.00143094 0.00655069 0.126868 +EDGE3 1778 1827 -5.24652 -7.67455 -3.91106 -0.00828671 0.00219441 -0.116085 +EDGE3 1779 1829 -4.85624 -0.00790438 -3.97365 -0.00696169 0.00174687 -0.00645857 +EDGE3 1778 1829 -5.43117 7.6233 -4.05676 0.00106848 -0.000318647 0.115528 +EDGE3 1779 1828 -5.24423 -7.63953 -3.90257 -0.00075998 0.000594329 -0.123725 +EDGE3 1780 1830 -4.87057 0.00515478 -3.98362 0.00546996 -0.00315436 0.0069375 +EDGE3 1779 1830 -5.43175 7.62003 -4.04903 -0.00392246 0.00482205 0.125278 +EDGE3 1780 1829 -5.24138 -7.63903 -3.89189 -0.0133333 0.00501157 -0.124783 +EDGE3 1781 1831 -4.87877 0.0097089 -3.9732 -0.00788364 -0.00197953 -0.00288576 +EDGE3 1780 1831 -5.45175 7.60775 -4.0593 -0.0126872 -0.00124283 0.122769 +EDGE3 1781 1830 -5.24778 -7.62665 -3.8814 -0.00427409 0.00249382 -0.130438 +EDGE3 1782 1832 -4.86631 0.0118038 -3.96201 -0.00163373 0.0072918 0.000677132 +EDGE3 1781 1832 -5.4327 7.58986 -4.048 0.00561931 0.00744887 0.1184 +EDGE3 1782 1831 -5.24733 -7.61608 -3.89572 0.000915572 0.00402821 -0.130495 +EDGE3 1783 1833 -4.88988 -0.00472914 -3.95962 0.00369753 -0.00203298 0.000583655 +EDGE3 1782 1833 -5.45712 7.57273 -4.04446 -0.00100832 0.00541403 0.121423 +EDGE3 1783 1832 -5.25898 -7.59289 -3.87893 -0.00039329 0.00460208 -0.12344 +EDGE3 1784 1834 -4.86922 0.0125244 -3.94841 -0.00592215 0.000160338 0.00502568 +EDGE3 1783 1834 -5.46661 7.55772 -4.02775 0.0042378 0.00751998 0.130127 +EDGE3 1784 1833 -5.25606 -7.5807 -3.86885 5.93134e-05 0.000569124 -0.116905 +EDGE3 1785 1835 -4.88149 0.0105198 -3.93681 0.00343804 -0.000274619 0.010429 +EDGE3 1784 1835 -5.46573 7.54569 -4.02339 -0.00300424 -0.0135432 0.122173 +EDGE3 1785 1834 -5.27237 -7.55795 -3.87117 0.000126786 -0.00402868 -0.127021 +EDGE3 1786 1836 -4.89184 -0.0145697 -3.9628 -0.00210342 -0.00478344 -0.00693923 +EDGE3 1785 1836 -5.4493 7.55279 -4.03184 -0.00269612 -0.00411308 0.124466 +EDGE3 1786 1835 -5.27193 -7.54063 -3.86363 0.00280101 -0.00196662 -0.119777 +EDGE3 1787 1837 -4.88842 -0.00321293 -3.93906 0.00602598 -0.000603456 -0.00268222 +EDGE3 1786 1837 -5.47898 7.54868 -4.02225 -0.00141627 0.00750055 0.131317 +EDGE3 1788 1838 -4.90806 0.00472187 -3.93172 0.00442237 -0.000908216 0.00505285 +EDGE3 1787 1836 -5.2731 -7.53022 -3.86533 -0.00178273 -0.00503991 -0.122143 +EDGE3 1787 1838 -5.4657 7.51714 -4.00098 -0.00906945 -0.00451026 0.131148 +EDGE3 1788 1837 -5.29103 -7.51311 -3.84877 0.00448476 0.00818726 -0.125253 +EDGE3 1789 1839 -4.89769 -0.0126705 -3.90722 0.00238446 -0.0063316 -0.000338521 +EDGE3 1788 1839 -5.48419 7.50244 -4.01409 -0.00149754 -0.00255201 0.125979 +EDGE3 1789 1838 -5.2746 -7.49417 -3.85077 0.0115566 -0.00551092 -0.126782 +EDGE3 1790 1840 -4.8991 -0.00610139 -3.91129 0.0116912 0.00982374 -0.00438881 +EDGE3 1789 1840 -5.47897 7.48023 -4.00684 0.0039925 -0.00210537 0.122402 +EDGE3 1790 1839 -5.27324 -7.50365 -3.83917 0.00366159 -0.000412353 -0.125702 +EDGE3 1790 1841 -5.49213 7.48938 -3.99377 -0.00126395 2.82117e-05 0.120728 +EDGE3 1791 1841 -4.92089 0.0042946 -3.91402 0.00642204 0.0125096 0.000488459 +EDGE3 1792 1842 -4.92189 -0.00420187 -3.91184 0.0055212 0.00621852 -0.00670769 +EDGE3 1791 1840 -5.30365 -7.5031 -3.82928 -0.00100965 0.00777671 -0.131089 +EDGE3 1791 1842 -5.49148 7.46466 -3.9785 0.00579941 -0.00322865 0.129423 +EDGE3 1792 1841 -5.28295 -7.46247 -3.83276 -0.00696141 -0.000117526 -0.133673 +EDGE3 1793 1843 -4.92649 -0.00829784 -3.87935 0.00587566 -0.00559562 0.00698386 +EDGE3 1792 1843 -5.49405 7.45133 -3.99029 0.000400062 0.00230338 0.131241 +EDGE3 1794 1844 -4.9141 -0.00722005 -3.88016 0.000240627 -0.00325098 0.00570124 +EDGE3 1793 1842 -5.30724 -7.48533 -3.82531 -0.000744931 0.00372683 -0.120967 +EDGE3 1793 1844 -5.4891 7.45599 -3.96953 -0.000777685 -0.000151992 0.121547 +EDGE3 1794 1843 -5.30437 -7.44963 -3.82908 0.00150096 -0.00565203 -0.112878 +EDGE3 1795 1845 -4.93328 0.0150752 -3.89674 -0.00461024 0.00428676 0.00176754 +EDGE3 1794 1845 -5.4987 7.41637 -3.97222 -0.00215865 -0.000715351 0.120075 +EDGE3 1795 1844 -5.30045 -7.45393 -3.80138 -0.00692858 0.0011518 -0.126936 +EDGE3 1796 1846 -4.94757 0.0103936 -3.85632 -0.00775139 -0.00739801 0.0022732 +EDGE3 1795 1846 -5.51218 7.42517 -3.96888 -0.00720216 -0.00591771 0.122204 +EDGE3 1796 1845 -5.31366 -7.43179 -3.77559 0.00383245 -0.00292236 -0.130379 +EDGE3 1797 1847 -4.94997 0.00257094 -3.88691 0.00191343 0.00143999 -0.00282743 +EDGE3 1796 1847 -5.51375 7.39662 -3.94741 -0.0146426 0.002678 0.138598 +EDGE3 1797 1846 -5.30228 -7.40807 -3.82299 0.00269726 -0.000520389 -0.122618 +EDGE3 1798 1848 -4.96212 -0.000484764 -3.87534 0.00585509 -0.00377764 0.00505864 +EDGE3 1797 1848 -5.53592 7.39659 -3.93433 -0.000820939 0.00368366 0.114748 +EDGE3 1798 1847 -5.31345 -7.4244 -3.78397 0.00102956 -0.00420212 -0.118345 +EDGE3 1799 1849 -4.95885 0.00559666 -3.84582 0.00533096 0.00582266 0.00149242 +EDGE3 1798 1849 -5.53871 7.36775 -3.94233 0.00142874 -0.00269586 0.113878 +EDGE3 1799 1848 -5.31104 -7.3862 -3.77125 0.00167784 0.000547142 -0.126564 +EDGE3 1799 1850 -5.53526 7.35893 -3.92174 -0.00668154 -0.00367834 0.11654 +EDGE3 1800 1850 -4.96405 0.011793 -3.84382 0.00311047 0.00118596 -0.0030939 +EDGE3 1801 1851 -4.97307 0.00993378 -3.85167 0.00242888 0.00183186 -0.000197758 +EDGE3 1800 1849 -5.33449 -7.38333 -3.77724 -0.00139834 -0.00285177 -0.127622 +EDGE3 1800 1851 -5.52924 7.36526 -3.92202 -0.00591262 -0.00520716 0.124196 +EDGE3 1801 1850 -5.3247 -7.3791 -3.76751 -0.000112635 -0.00521953 -0.124198 +EDGE3 1802 1852 -4.98923 0.0112162 -3.83481 0.0114993 -0.000606867 -5.62146e-05 +EDGE3 1801 1852 -5.53664 7.34147 -3.92305 0.00301946 0.00560317 0.130139 +EDGE3 1802 1851 -5.33904 -7.3548 -3.77752 0.00361972 -0.00670066 -0.125198 +EDGE3 1803 1853 -4.9857 -0.0110467 -3.84025 -0.00147163 0.00723585 -0.00126161 +EDGE3 1802 1853 -5.54421 7.30394 -3.917 0.0107962 -0.00472256 0.121317 +EDGE3 1803 1852 -5.3286 -7.34193 -3.74367 -0.00344636 -0.000315943 -0.124393 +EDGE3 1803 1854 -5.55231 7.30411 -3.92736 0.000390471 0.00218551 0.132627 +EDGE3 1804 1854 -4.98844 0.01409 -3.82544 -0.0118589 -0.00772716 0.00283645 +EDGE3 1805 1855 -4.9818 -0.0018531 -3.84302 -0.0041274 0.00697165 -0.00486252 +EDGE3 1804 1853 -5.33442 -7.31912 -3.76166 -0.00314441 -0.00179554 -0.123176 +EDGE3 1804 1855 -5.54031 7.30667 -3.8845 -0.00337083 -0.00454509 0.122479 +EDGE3 1805 1854 -5.35693 -7.32863 -3.74797 -0.00221866 -0.00456363 -0.125097 +EDGE3 1806 1856 -4.98995 0.0114391 -3.81675 0.00821867 -0.00216048 0.00135355 +EDGE3 1805 1856 -5.55899 7.29332 -3.87808 0.00270258 0.00302759 0.123812 +EDGE3 1806 1855 -5.34247 -7.30931 -3.74234 -0.00421265 -0.0073021 -0.122341 +EDGE3 1807 1857 -5.00371 -0.00744606 -3.79101 -0.00283192 -0.00102042 -0.00199942 +EDGE3 1806 1857 -5.55272 7.26499 -3.87098 0.00288564 -0.00496099 0.115404 +EDGE3 1807 1856 -5.34783 -7.28885 -3.75279 -0.00337934 0.00858725 -0.114765 +EDGE3 1807 1858 -5.55181 7.28294 -3.88505 0.00307232 0.00378405 0.125469 +EDGE3 1808 1858 -5.00619 0.00546765 -3.79761 -0.00496154 0.0041372 0.0088314 +EDGE3 1809 1859 -5.02435 0.00583731 -3.78925 0.000721523 -0.00526779 -0.00757855 +EDGE3 1808 1857 -5.34959 -7.26569 -3.72795 -0.0106843 0.000171288 -0.124213 +EDGE3 1808 1859 -5.57999 7.25355 -3.88685 0.00157848 -0.00210909 0.11749 +EDGE3 1809 1858 -5.36856 -7.24227 -3.73412 -0.00294689 0.00179432 -0.12192 +EDGE3 1810 1860 -5.00022 -0.0147499 -3.77794 0.00391133 0.00519094 0.00577906 +EDGE3 1809 1860 -5.59024 7.24121 -3.86817 9.94707e-05 0.00979787 0.131085 +EDGE3 1810 1859 -5.35348 -7.24187 -3.73198 -0.000677837 0.000875136 -0.126649 +EDGE3 1811 1861 -5.00657 -0.0110183 -3.78119 0.00131098 -0.00759608 0.0067793 +EDGE3 1810 1861 -5.55535 7.21628 -3.87787 -0.0076914 0.00218581 0.131753 +EDGE3 1812 1862 -5.01181 -0.0126223 -3.77806 0.00703621 -0.00607796 -0.00369898 +EDGE3 1811 1860 -5.39156 -7.25552 -3.70554 -0.00371105 -0.00723323 -0.128795 +EDGE3 1811 1862 -5.58522 7.19873 -3.85832 -0.00294616 -0.0051768 0.127938 +EDGE3 1812 1861 -5.369 -7.24147 -3.69519 0.00103907 -0.0110418 -0.121532 +EDGE3 1812 1863 -5.5897 7.20084 -3.82544 0.00370806 0.000506186 0.129033 +EDGE3 1813 1863 -5.04907 0.00907158 -3.77108 0.013883 -0.00806322 0.0140914 +EDGE3 1814 1864 -5.03323 0.00949314 -3.74804 0.000907748 0.00580174 -0.00726649 +EDGE3 1813 1862 -5.36551 -7.20569 -3.68941 -0.00371072 0.00827723 -0.121557 +EDGE3 1813 1864 -5.60027 7.19589 -3.84176 0.00669964 -0.00107158 0.112612 +EDGE3 1814 1863 -5.38367 -7.19072 -3.69206 -0.00349699 0.00266039 -0.138488 +EDGE3 1815 1865 -5.02366 0.00246223 -3.73602 0.00862934 -0.00955701 0.00417376 +EDGE3 1814 1865 -5.58438 7.16074 -3.83254 0.00255022 -0.00412662 0.12528 +EDGE3 1815 1864 -5.40237 -7.17777 -3.69637 0.00666684 -0.000597053 -0.132842 +EDGE3 1815 1866 -5.57288 7.15153 -3.8424 -0.00262732 0.000943838 0.130775 +EDGE3 1816 1866 -5.039 0.00560424 -3.74756 -0.00698861 0.0015765 -0.00673983 +EDGE3 1817 1867 -5.05844 0.0258366 -3.76123 0.00451125 0.0122019 -0.00499206 +EDGE3 1816 1865 -5.37799 -7.17988 -3.6876 -0.00166073 -0.0103255 -0.120544 +EDGE3 1817 1866 -5.4046 -7.18739 -3.65828 0.00430793 -0.00822985 -0.122994 +EDGE3 1816 1867 -5.5914 7.12999 -3.82889 0.00581652 0.003029 0.132242 +EDGE3 1818 1868 -5.05815 0.00724027 -3.73092 -0.00439417 0.00764833 0.000767403 +EDGE3 1817 1868 -5.57902 7.14382 -3.80409 -0.0104346 0.00884767 0.119018 +EDGE3 1818 1867 -5.40268 -7.15587 -3.66947 0.00152587 0.00414913 -0.133321 +EDGE3 1819 1869 -5.03711 0.00814831 -3.72953 -0.00464985 0.00440622 -0.00144952 +EDGE3 1818 1869 -5.58991 7.14242 -3.8123 -0.0053982 -0.00642717 0.130444 +EDGE3 1819 1868 -5.40839 -7.15419 -3.66599 -0.00850906 -0.00177424 -0.123692 +EDGE3 1820 1870 -5.05813 0.021501 -3.71573 -0.00414362 0.0086448 -0.00285269 +EDGE3 1819 1870 -5.61953 7.10038 -3.80619 0.00568748 5.79418e-05 0.125191 +EDGE3 1820 1869 -5.39741 -7.11843 -3.65781 -0.000391103 0.00157398 -0.124734 +EDGE3 1821 1871 -5.0736 0.0212171 -3.71211 -2.08887e-05 -0.00460146 -0.002584 +EDGE3 1820 1871 -5.61621 7.08876 -3.78497 0.00397592 0.00555962 0.12192 +EDGE3 1821 1870 -5.41197 -7.11014 -3.65301 -0.00638121 0.00527497 -0.131208 +EDGE3 1822 1872 -5.04741 0.00870519 -3.70789 -0.000230292 -0.000873144 0.00307456 +EDGE3 1821 1872 -5.60137 7.087 -3.77871 0.00248309 -0.00696512 0.128778 +EDGE3 1822 1871 -5.41983 -7.1034 -3.65369 0.00162581 0.00213314 -0.124818 +EDGE3 1823 1873 -5.05267 0.00524996 -3.71638 -0.00579428 0.00923454 -0.00326197 +EDGE3 1822 1873 -5.61598 7.0637 -3.7876 0.00116371 0.00409724 0.12622 +EDGE3 1823 1872 -5.40061 -7.09643 -3.64977 -0.00558031 0.00523821 -0.129583 +EDGE3 1824 1874 -5.08303 -0.010495 -3.69223 0.00382765 0.000456398 0.0010409 +EDGE3 1823 1874 -5.61648 7.06308 -3.78506 -0.00355655 -0.00294706 0.12362 +EDGE3 1824 1873 -5.41476 -7.07109 -3.65242 0.00937302 0.00468833 -0.133854 +EDGE3 1825 1875 -5.10877 0.012724 -3.69363 -0.0103521 0.000995326 -0.00549889 +EDGE3 1824 1875 -5.62951 7.0428 -3.75334 0.00732055 0.00438405 0.126672 +EDGE3 1825 1874 -5.43053 -7.04946 -3.61772 0.00284715 -0.00141089 -0.119666 +EDGE3 1826 1876 -5.09569 -0.0024769 -3.67861 -0.00398303 -0.00362376 0.0050859 +EDGE3 1825 1876 -5.63029 7.02696 -3.76381 0.00652574 0.00265989 0.12324 +EDGE3 1826 1875 -5.42519 -7.0529 -3.63365 -0.00501932 -0.00331789 -0.124147 +EDGE3 1827 1877 -5.08086 -0.00713862 -3.67703 -0.00143428 -0.00656485 0.00515458 +EDGE3 1826 1877 -5.61835 7.02542 -3.75782 0.0075002 0.00321902 0.122756 +EDGE3 1827 1876 -5.44305 -7.03215 -3.61603 0.00146615 -0.00168102 -0.124775 +EDGE3 1828 1878 -5.09889 0.00198029 -3.6759 -0.00106914 -0.00655782 -0.00123333 +EDGE3 1827 1878 -5.6165 7.01785 -3.76056 -0.00331247 0.00053484 0.124608 +EDGE3 1828 1877 -5.44349 -7.01581 -3.6011 -0.00364302 0.00268327 -0.121456 +EDGE3 1829 1879 -5.08557 0.00965347 -3.67132 0.00061807 0.000630563 -0.000121221 +EDGE3 1828 1879 -5.63911 6.99177 -3.75324 -0.00793607 0.000761124 0.123011 +EDGE3 1829 1878 -5.44342 -6.99751 -3.60598 0.00641459 0.00331993 -0.126517 +EDGE3 1830 1880 -5.10409 -0.0011256 -3.6625 0.000963328 0.00145529 -0.00309162 +EDGE3 1829 1880 -5.64931 6.98027 -3.7556 -0.00243981 -0.000890899 0.120572 +EDGE3 1830 1879 -5.44327 -6.99225 -3.57168 0.00740068 -0.00230545 -0.128326 +EDGE3 1831 1881 -5.11302 -0.00354604 -3.64876 0.000544769 -0.00178334 -0.00879484 +EDGE3 1830 1881 -5.63538 6.98623 -3.72734 0.00257429 -0.00418372 0.123594 +EDGE3 1831 1880 -5.44074 -6.97584 -3.59001 0.00594625 0.00585397 -0.138544 +EDGE3 1832 1882 -5.12505 -0.0118521 -3.6498 -0.00705581 0.000998992 -0.00246359 +EDGE3 1831 1882 -5.64366 6.94987 -3.72683 -0.00197274 0.00102544 0.125517 +EDGE3 1832 1881 -5.45257 -6.96809 -3.58824 0.0030764 -1.95593e-05 -0.125861 +EDGE3 1833 1883 -5.10776 0.00187118 -3.64236 -0.00368273 0.00484534 -0.00368708 +EDGE3 1832 1883 -5.64553 6.94502 -3.71171 -0.00451129 -0.00357991 0.125969 +EDGE3 1833 1882 -5.44584 -6.9658 -3.55775 0.000593117 -0.00383649 -0.124425 +EDGE3 1834 1884 -5.13371 -0.00673398 -3.62898 -0.000392778 -0.0039544 0.00365269 +EDGE3 1833 1884 -5.64997 6.91941 -3.7193 -0.000514329 0.00292452 0.126277 +EDGE3 1834 1883 -5.45836 -6.93094 -3.5545 -0.000628971 0.0130496 -0.134989 +EDGE3 1835 1885 -5.12279 0.000452955 -3.63925 -0.00205259 0.00359525 0.00813425 +EDGE3 1834 1885 -5.6488 6.89551 -3.70261 0.00282603 -0.00322824 0.122874 +EDGE3 1835 1884 -5.46095 -6.92289 -3.56842 -0.00644427 -0.00466636 -0.127138 +EDGE3 1836 1886 -5.11736 0.00438354 -3.64504 -0.000908111 0.00300209 0.00391021 +EDGE3 1835 1886 -5.65238 6.8981 -3.69778 0.00270809 -0.000174884 0.126167 +EDGE3 1836 1885 -5.48396 -6.91899 -3.55135 -0.00322862 -0.00161251 -0.127153 +EDGE3 1837 1887 -5.13166 0.00167848 -3.61639 0.00234152 -0.00533239 0.00776714 +EDGE3 1836 1887 -5.67315 6.883 -3.67419 -0.00619349 0.00493397 0.127774 +EDGE3 1837 1886 -5.469 -6.90551 -3.56312 -0.0121594 -0.0025803 -0.124952 +EDGE3 1838 1888 -5.15401 -0.00535823 -3.61032 -0.000269992 -0.0133699 -0.00501315 +EDGE3 1837 1888 -5.66973 6.86408 -3.69924 0.00377233 0.00113323 0.123228 +EDGE3 1838 1887 -5.478 -6.88341 -3.53705 0.00121067 0.00338511 -0.131711 +EDGE3 1839 1889 -5.15816 0.012348 -3.59288 -0.00176348 0.00145552 -0.00142139 +EDGE3 1838 1889 -5.67174 6.84919 -3.68864 -0.00348412 0.0058242 0.129062 +EDGE3 1839 1888 -5.46317 -6.857 -3.53726 0.0094118 0.0028332 -0.123841 +EDGE3 1840 1890 -5.16255 -0.00360815 -3.59699 -0.00127088 0.00059433 -0.00135448 +EDGE3 1839 1890 -5.68185 6.83724 -3.66692 -0.00576477 -0.00066441 0.122029 +EDGE3 1840 1889 -5.46265 -6.86421 -3.52256 -0.000274476 -0.00102173 -0.128663 +EDGE3 1841 1891 -5.1708 -0.0120635 -3.58109 -0.00170977 -0.00939015 0.00776685 +EDGE3 1840 1891 -5.69528 6.83548 -3.67026 -0.000547713 0.0188776 0.127499 +EDGE3 1841 1890 -5.49495 -6.83944 -3.51688 0.00158725 0.00111175 -0.124543 +EDGE3 1842 1892 -5.15973 0.000744055 -3.58212 -0.00408669 -0.00243039 0.00247302 +EDGE3 1841 1892 -5.69756 6.82574 -3.64871 -0.00189009 -0.00380789 0.131453 +EDGE3 1842 1891 -5.49737 -6.85385 -3.52437 -0.0041385 0.00639935 -0.130551 +EDGE3 1843 1893 -5.15553 -0.000184333 -3.594 -0.00141491 -0.0113157 -0.00697898 +EDGE3 1842 1893 -5.6959 6.81562 -3.65725 0.00642619 0.00368315 0.129043 +EDGE3 1843 1892 -5.49346 -6.78955 -3.50982 0.00242095 0.00595954 -0.129134 +EDGE3 1844 1894 -5.19057 -0.00850402 -3.55761 0.0037234 0.000509833 -0.00447113 +EDGE3 1843 1894 -5.69247 6.77909 -3.64074 -0.00045393 0.00251018 0.114145 +EDGE3 1844 1893 -5.48665 -6.81181 -3.49552 -0.00466797 -0.000512546 -0.129289 +EDGE3 1845 1895 -5.19393 -0.0053208 -3.56502 0.00123233 -0.00653559 0.0109222 +EDGE3 1844 1895 -5.71488 6.78204 -3.63139 -0.00317601 -0.00313305 0.126885 +EDGE3 1845 1894 -5.50055 -6.78309 -3.49317 -0.00721908 -0.000518441 -0.114114 +EDGE3 1846 1896 -5.18598 0.00670256 -3.55278 0.00072354 0.00793236 -0.00241618 +EDGE3 1845 1896 -5.70185 6.77358 -3.63124 0.00626283 -0.00654293 0.134823 +EDGE3 1846 1895 -5.49589 -6.79489 -3.50549 0.000323905 -0.00142103 -0.124881 +EDGE3 1847 1897 -5.18581 -0.0212236 -3.54927 -0.00598339 0.00263016 0.000319618 +EDGE3 1846 1897 -5.71812 6.76556 -3.61555 0.00525337 -0.0119964 0.131982 +EDGE3 1847 1896 -5.50499 -6.76911 -3.47207 -0.000959178 0.00362545 -0.128037 +EDGE3 1848 1898 -5.19506 0.0152057 -3.53071 -0.014967 -0.0170116 -0.00631657 +EDGE3 1847 1898 -5.71701 6.73923 -3.59891 -0.000968431 0.00451709 0.127672 +EDGE3 1848 1897 -5.48812 -6.75158 -3.47401 0.0164432 0.00327616 -0.124409 +EDGE3 1849 1899 -5.18717 0.0029429 -3.55133 0.00719912 -0.000800041 -0.00267123 +EDGE3 1848 1899 -5.71834 6.73421 -3.60384 -0.00817363 0.00213857 0.1205 +EDGE3 1849 1898 -5.50698 -6.73763 -3.47791 -8.89939e-05 -0.00707023 -0.130531 +EDGE3 1850 1900 -5.19995 0.00219266 -3.53971 -0.006476 -0.00103317 0.00292286 +EDGE3 1849 1900 -5.71914 6.73051 -3.61343 -0.00169842 -0.000604634 0.127345 +EDGE3 1850 1899 -5.49664 -6.71823 -3.47202 0.00411462 0.00659787 -0.129788 +EDGE3 1851 1901 -5.21099 -0.00039306 -3.51251 0.00423305 -0.000650649 -0.0125266 +EDGE3 1850 1901 -5.71778 6.6809 -3.60384 -0.00638793 0.00241048 0.128158 +EDGE3 1851 1900 -5.51004 -6.72334 -3.45522 0.000411477 0.000994537 -0.12933 +EDGE3 1852 1902 -5.19587 0.0102717 -3.52158 -0.000126853 -0.000170372 -0.00827045 +EDGE3 1851 1902 -5.72771 6.66201 -3.59414 -0.0097872 -4.3307e-05 0.123124 +EDGE3 1852 1901 -5.52918 -6.69913 -3.43743 -0.00323176 -0.00217446 -0.125943 +EDGE3 1853 1903 -5.21226 0.0042453 -3.5288 0.00061414 -7.9598e-05 0.000548606 +EDGE3 1852 1903 -5.7323 6.67915 -3.57668 -0.00985475 0.00645645 0.123548 +EDGE3 1853 1902 -5.50293 -6.69196 -3.45305 -0.00542387 0.0123272 -0.120223 +EDGE3 1854 1904 -5.2032 -0.013113 -3.50715 -0.0125727 -0.000931647 0.00349719 +EDGE3 1853 1904 -5.72788 6.65255 -3.58224 0.0136325 0.00113703 0.129825 +EDGE3 1854 1903 -5.51908 -6.70721 -3.44234 0.00532937 0.00872313 -0.131277 +EDGE3 1855 1905 -5.20254 0.00050389 -3.47949 0.00392098 -0.00269351 -0.00563944 +EDGE3 1854 1905 -5.73292 6.65004 -3.57074 -0.00729607 0.00821942 0.12639 +EDGE3 1855 1904 -5.54267 -6.65048 -3.43759 0.00467327 -0.000531575 -0.124383 +EDGE3 1856 1906 -5.22828 0.0117716 -3.49639 0.00328251 0.00108014 0.00775688 +EDGE3 1855 1906 -5.73227 6.64264 -3.55968 -0.00499372 -0.0135159 0.131905 +EDGE3 1856 1905 -5.53262 -6.63145 -3.42776 0.000654223 0.000337119 -0.119101 +EDGE3 1857 1907 -5.23207 -0.00951556 -3.47987 0.00469953 -0.00238054 0.000414118 +EDGE3 1856 1907 -5.74549 6.61612 -3.56477 -0.00971957 0.00628617 0.123235 +EDGE3 1857 1906 -5.53195 -6.6512 -3.41654 0.000667421 -0.0026193 -0.124497 +EDGE3 1858 1908 -5.24507 0.00851595 -3.48632 -0.00516835 -0.00457761 0.00514431 +EDGE3 1857 1908 -5.74495 6.62652 -3.54158 -0.00278559 0.00405758 0.137789 +EDGE3 1858 1907 -5.53512 -6.62543 -3.40515 -0.0110708 -0.0111325 -0.127151 +EDGE3 1859 1909 -5.23841 0.017278 -3.46855 0.0021455 -0.00460282 -0.00372899 +EDGE3 1858 1909 -5.76631 6.59822 -3.53293 0.00305393 0.00719496 0.127431 +EDGE3 1859 1908 -5.55525 -6.61155 -3.40748 0.00116366 -0.00389885 -0.128165 +EDGE3 1860 1910 -5.23101 0.00499385 -3.48303 0.00187549 0.000302053 0.00418708 +EDGE3 1859 1910 -5.7616 6.57211 -3.55858 -0.00767666 -0.00408892 0.12042 +EDGE3 1860 1909 -5.55524 -6.60557 -3.39136 0.000274031 0.004333 -0.126034 +EDGE3 1861 1911 -5.26239 -0.0008173 -3.45123 0.0044654 0.000274662 0.00833256 +EDGE3 1860 1911 -5.76661 6.55365 -3.5219 -0.00353071 0.00219628 0.125549 +EDGE3 1861 1910 -5.54592 -6.56799 -3.38505 0.00590811 0.000164157 -0.130709 +EDGE3 1862 1912 -5.24175 -0.014365 -3.44558 0.000692072 -0.00263768 -0.00574217 +EDGE3 1861 1912 -5.77412 6.55102 -3.52617 0.0099999 -0.00317613 0.127624 +EDGE3 1862 1911 -5.56218 -6.57174 -3.38229 0.00523684 0.0133906 -0.12559 +EDGE3 1863 1913 -5.26658 0.00369651 -3.44044 0.00437295 -0.00271726 0.000465584 +EDGE3 1862 1913 -5.74915 6.54269 -3.51098 -0.00175548 -0.00677235 0.129113 +EDGE3 1863 1912 -5.56335 -6.54751 -3.40561 -0.00483739 0.00913401 -0.130001 +EDGE3 1864 1914 -5.26189 -0.00302098 -3.44183 -0.00987291 0.00836309 -0.000794343 +EDGE3 1863 1914 -5.76363 6.53738 -3.5149 -0.00215253 -0.00215478 0.126919 +EDGE3 1864 1913 -5.56994 -6.54897 -3.38404 0.000230485 -0.00687689 -0.116027 +EDGE3 1865 1915 -5.26253 -0.00364288 -3.4411 0.00348503 0.00159369 -0.0101161 +EDGE3 1864 1915 -5.77426 6.514 -3.50853 -0.00113978 0.00256539 0.129222 +EDGE3 1865 1914 -5.56667 -6.5213 -3.36661 0.00798109 0.0111652 -0.125763 +EDGE3 1866 1916 -5.27022 0.00511204 -3.42189 0.00470469 -0.00476784 0.00511343 +EDGE3 1865 1916 -5.75982 6.50099 -3.5042 -0.000352116 0.000689981 0.129946 +EDGE3 1866 1915 -5.56872 -6.51007 -3.35244 0.00191356 0.00793742 -0.132836 +EDGE3 1867 1917 -5.27055 0.0126347 -3.42565 0.00743785 0.00161532 -0.00466631 +EDGE3 1866 1917 -5.78311 6.47578 -3.45933 0.00320478 0.00423008 0.134552 +EDGE3 1867 1916 -5.56709 -6.4858 -3.34909 -0.00245744 -0.00333526 -0.123421 +EDGE3 1868 1918 -5.27602 -0.0188264 -3.41401 0.00550606 0.0087008 -0.00582172 +EDGE3 1867 1918 -5.7716 6.4749 -3.49017 -0.00930914 0.000555756 0.125922 +EDGE3 1868 1917 -5.57969 -6.48561 -3.34975 -0.00698191 -0.0044222 -0.132387 +EDGE3 1869 1919 -5.29277 -0.0136755 -3.41526 0.00207453 0.00400624 -0.00583018 +EDGE3 1868 1919 -5.79274 6.45672 -3.49303 -0.00540824 -0.0103684 0.129757 +EDGE3 1869 1918 -5.57228 -6.47328 -3.32796 -0.00881996 -0.00335636 -0.120297 +EDGE3 1870 1920 -5.28728 0.00328401 -3.38105 -0.00361681 0.00130894 -0.00400956 +EDGE3 1869 1920 -5.80512 6.43933 -3.46979 0.00870172 0.00683248 0.12871 +EDGE3 1870 1919 -5.5975 -6.47069 -3.34495 -0.00497276 -0.00156028 -0.121443 +EDGE3 1871 1921 -5.26175 0.00680745 -3.38121 -0.0064361 3.41879e-05 0.00694569 +EDGE3 1870 1921 -5.78615 6.44626 -3.47955 -0.00616073 0.00516728 0.129516 +EDGE3 1871 1920 -5.58841 -6.45249 -3.30494 -0.00261774 -0.00355625 -0.126504 +EDGE3 1872 1922 -5.3031 0.00467001 -3.37482 0.00446262 0.00672643 -0.00653805 +EDGE3 1871 1922 -5.78552 6.42387 -3.44719 0.00639153 -0.000512289 0.120192 +EDGE3 1872 1921 -5.58702 -6.44166 -3.32471 -0.00179406 -0.00194478 -0.123637 +EDGE3 1873 1923 -5.30883 0.0103124 -3.36053 0.00337579 -0.00301483 0.00144519 +EDGE3 1872 1923 -5.80598 6.40773 -3.45752 0.00263373 -0.00111141 0.128788 +EDGE3 1873 1922 -5.58176 -6.41815 -3.30883 0.00270731 -0.00569288 -0.124409 +EDGE3 1874 1924 -5.2837 -0.00793459 -3.35649 -0.00149375 -0.00818643 -6.70774e-05 +EDGE3 1873 1924 -5.79841 6.39653 -3.45627 -0.0036596 0.00269822 0.121319 +EDGE3 1874 1923 -5.58129 -6.40258 -3.31529 0.0039288 -0.00182464 -0.127105 +EDGE3 1875 1925 -5.31893 -0.00955089 -3.36933 0.000646228 -0.0049979 0.00289322 +EDGE3 1874 1925 -5.80502 6.40053 -3.42968 0.00225727 -0.00166103 0.136251 +EDGE3 1875 1924 -5.60889 -6.40082 -3.28398 0.0068033 -0.0114332 -0.117295 +EDGE3 1876 1926 -5.29092 0.00384964 -3.35334 0.00352746 -0.00260534 -0.00171604 +EDGE3 1875 1926 -5.81785 6.36343 -3.43491 0.0104818 0.00745003 0.127596 +EDGE3 1877 1927 -5.31817 -0.00701177 -3.34764 -0.00654147 0.00101238 -0.00180559 +EDGE3 1876 1925 -5.61908 -6.38953 -3.2925 0.0079494 -0.00333023 -0.134583 +EDGE3 1876 1927 -5.80711 6.35809 -3.41266 0.00314591 0.00213415 0.124744 +EDGE3 1877 1926 -5.60443 -6.36522 -3.28619 0.000509374 -0.0141503 -0.125705 +EDGE3 1878 1928 -5.32146 0.00114493 -3.36044 0.00471224 -0.000932439 -0.00253407 +EDGE3 1877 1928 -5.81012 6.34433 -3.41912 0.000429312 -0.00331361 0.131045 +EDGE3 1878 1927 -5.62879 -6.33611 -3.2787 0.00194759 -0.00608617 -0.124952 +EDGE3 1879 1929 -5.30061 0.00434193 -3.34086 -0.00311293 0.00926704 0.00398527 +EDGE3 1878 1929 -5.83173 6.31906 -3.38828 0.00133753 0.00265985 0.119534 +EDGE3 1879 1928 -5.6017 -6.34623 -3.26147 -0.00601599 -0.0056844 -0.122325 +EDGE3 1880 1930 -5.33595 0.00510348 -3.33204 -0.00615293 -0.00363009 -0.00124265 +EDGE3 1879 1930 -5.8464 6.3125 -3.39884 -0.00748567 -0.00479524 0.122864 +EDGE3 1880 1929 -5.6204 -6.322 -3.29004 -0.00737452 0.000543084 -0.127591 +EDGE3 1881 1931 -5.32376 0.0188107 -3.32871 0.00226888 0.00114298 -0.000860421 +EDGE3 1880 1931 -5.84215 6.28429 -3.38561 -0.00635031 0.000640743 0.123886 +EDGE3 1881 1930 -5.60928 -6.31502 -3.26762 0.00474297 0.00362334 -0.12711 +EDGE3 1882 1932 -5.34941 -0.0145751 -3.32067 -0.00551713 -0.00506063 -0.00713923 +EDGE3 1881 1932 -5.83336 6.28296 -3.40341 0.00217309 -0.0117383 0.118477 +EDGE3 1882 1931 -5.62262 -6.31396 -3.26203 0.000644942 -0.000389022 -0.116143 +EDGE3 1883 1933 -5.33678 -0.00176256 -3.30723 -0.008553 -0.000814676 -0.00253509 +EDGE3 1882 1933 -5.83333 6.27239 -3.37095 -0.00195533 0.0110726 0.121232 +EDGE3 1884 1934 -5.33191 -0.0135106 -3.29591 -0.000979606 -0.0083674 -0.000716074 +EDGE3 1883 1932 -5.62804 -6.27797 -3.25187 0.00240717 -0.00374037 -0.116508 +EDGE3 1883 1934 -5.85036 6.24668 -3.38002 0.00563628 0.00751899 0.124951 +EDGE3 1884 1933 -5.63223 -6.27262 -3.21787 -0.00632356 0.00639955 -0.121825 +EDGE3 1885 1935 -5.3417 0.000777446 -3.30502 -0.00283064 -0.00411176 0.00309049 +EDGE3 1884 1935 -5.83889 6.2415 -3.36858 0.00738546 0.00258514 0.121209 +EDGE3 1885 1934 -5.64838 -6.27245 -3.25528 0.000167137 0.00424364 -0.132344 +EDGE3 1886 1936 -5.34165 0.0129769 -3.28782 -0.00222081 -0.000199987 0.00869588 +EDGE3 1885 1936 -5.8471 6.24331 -3.35897 0.00645663 -0.000276771 0.126907 +EDGE3 1886 1935 -5.63422 -6.24597 -3.23288 -0.00164495 -0.000206825 -0.124356 +EDGE3 1887 1937 -5.3496 -0.00336737 -3.29753 0.00189651 -0.00379822 -0.00169804 +EDGE3 1886 1937 -5.84256 6.22436 -3.35095 0.00211102 -0.00436196 0.121722 +EDGE3 1888 1938 -5.35685 0.00872093 -3.28596 0.00318347 -0.0013277 0.00622994 +EDGE3 1887 1936 -5.6312 -6.23387 -3.21444 0.00798513 -0.000410798 -0.130586 +EDGE3 1887 1938 -5.85449 6.20253 -3.34263 -0.00654313 -0.00814656 0.128688 +EDGE3 1888 1937 -5.64048 -6.22007 -3.22368 0.00135903 -0.00901814 -0.118991 +EDGE3 1889 1939 -5.34808 0.01118 -3.28136 -0.00532863 0.00238961 -0.000422936 +EDGE3 1888 1939 -5.85263 6.19161 -3.33252 -0.0055176 0.00221429 0.12737 +EDGE3 1889 1938 -5.64984 -6.19307 -3.21376 0.00183303 -0.00254312 -0.126056 +EDGE3 1890 1940 -5.36943 -0.0179558 -3.2711 0.00212436 0.000554887 -0.00313354 +EDGE3 1889 1940 -5.86675 6.17547 -3.33117 0.00190882 -0.0012467 0.124803 +EDGE3 1890 1939 -5.65898 -6.1785 -3.18345 -0.000415469 0.00603812 -0.122632 +EDGE3 1891 1941 -5.36203 0.00421967 -3.26074 0.00305489 -0.00262201 -0.00121929 +EDGE3 1890 1941 -5.85405 6.15938 -3.31977 0.00346342 -0.00107154 0.125635 +EDGE3 1891 1940 -5.63669 -6.19038 -3.1908 0.00373237 0.0015159 -0.12711 +EDGE3 1892 1942 -5.36357 0.00160392 -3.27006 -0.00708724 0.00393476 -0.00414916 +EDGE3 1891 1942 -5.87015 6.16503 -3.30907 0.0018498 0.000423082 0.127875 +EDGE3 1892 1941 -5.6386 -6.1559 -3.18604 0.00219947 -0.00485354 -0.119984 +EDGE3 1893 1943 -5.35773 -0.0038269 -3.25575 -0.00235348 0.000834121 0.00152251 +EDGE3 1892 1943 -5.87439 6.13316 -3.30729 -0.000247705 -0.000988456 0.125336 +EDGE3 1893 1942 -5.64967 -6.16036 -3.19567 0.00188488 0.000852968 -0.125223 +EDGE3 1894 1944 -5.37145 -0.0092327 -3.24162 0.000189917 0.00433797 0.00365577 +EDGE3 1893 1944 -5.8763 6.11825 -3.30746 -0.000117102 0.00196663 0.130015 +EDGE3 1894 1943 -5.66446 -6.14086 -3.16173 -0.00212123 0.000973495 -0.129907 +EDGE3 1895 1945 -5.38967 0.0037349 -3.22818 0.0116071 0.000677882 -0.00259782 +EDGE3 1894 1945 -5.88192 6.11668 -3.28301 -0.00144359 0.00372206 0.121672 +EDGE3 1895 1944 -5.6635 -6.10784 -3.16296 0.00731365 0.0017216 -0.12533 +EDGE3 1896 1946 -5.39573 0.00657945 -3.22439 0.000317883 -0.00183642 0.000368526 +EDGE3 1895 1946 -5.86667 6.09899 -3.29684 -0.000263134 -0.0015017 0.12179 +EDGE3 1896 1945 -5.67412 -6.08366 -3.16545 0.0052457 0.00250773 -0.121947 +EDGE3 1897 1947 -5.39357 0.00283829 -3.24237 -0.00228744 0.000173388 -0.00512873 +EDGE3 1896 1947 -5.87511 6.08954 -3.29632 0.00478532 0.00304064 0.135981 +EDGE3 1897 1946 -5.65847 -6.08136 -3.16787 0.000409056 0.00413764 -0.125668 +EDGE3 1898 1948 -5.3819 0.00821504 -3.18909 -0.000252837 0.00906003 -0.000641906 +EDGE3 1897 1948 -5.88923 6.05664 -3.2788 -0.00104689 -0.0095697 0.12056 +EDGE3 1898 1947 -5.65132 -6.06553 -3.15595 -0.0055003 -0.000760796 -0.12838 +EDGE3 1898 1949 -5.8924 6.0315 -3.28629 0.00283168 0.00015285 0.127207 +EDGE3 1899 1949 -5.41409 0.004899 -3.18113 -0.0128026 0.00242451 -0.00301246 +EDGE3 1900 1950 -5.40555 0.00449769 -3.19031 -0.000773293 0.0085803 -0.000855349 +EDGE3 1899 1948 -5.69256 -6.07514 -3.13826 -0.00385793 4.38254e-06 -0.126257 +EDGE3 1899 1950 -5.88508 6.03227 -3.26025 0.0021558 -0.000973312 0.122006 +EDGE3 1900 1949 -5.66991 -6.05268 -3.13665 0.000980291 0.000524749 -0.115893 +EDGE3 1901 1951 -5.41686 -0.00564788 -3.20732 -0.00363837 -0.00610922 -0.000700343 +EDGE3 1900 1951 -5.89034 6.02068 -3.25921 0.00998144 0.0066982 0.119863 +EDGE3 1901 1950 -5.68476 -6.04687 -3.11809 -0.00232885 -0.00152281 -0.118596 +EDGE3 1902 1952 -5.43038 -0.00833196 -3.19583 -0.00703495 -0.00572986 0.00186532 +EDGE3 1901 1952 -5.88789 6.01479 -3.23085 -0.00535047 -0.0103298 0.121357 +EDGE3 1902 1951 -5.6708 -6.03229 -3.11827 -0.000596574 -0.00443279 -0.134258 +EDGE3 1903 1953 -5.42626 0.00738079 -3.17987 0.00709033 0.00365837 -0.00206977 +EDGE3 1902 1953 -5.89223 5.98688 -3.25339 -0.00229023 0.00156955 0.128186 +EDGE3 1903 1952 -5.68034 -6.02174 -3.1325 0.00753471 -0.000517762 -0.126598 +EDGE3 1904 1954 -5.42408 0.0199544 -3.16109 -0.00149456 -0.00244919 0.00214676 +EDGE3 1903 1954 -5.90704 5.9817 -3.2394 -0.0106598 0.00431322 0.125747 +EDGE3 1904 1953 -5.70119 -5.98925 -3.11563 -0.00611544 -0.0017025 -0.127205 +EDGE3 1905 1955 -5.4262 -0.00225865 -3.17554 -0.00220082 0.00670061 -0.00840319 +EDGE3 1904 1955 -5.9073 5.96329 -3.24276 -0.00635743 -0.00742364 0.121181 +EDGE3 1905 1954 -5.67821 -5.98115 -3.11112 -0.00418176 0.00724216 -0.123352 +EDGE3 1906 1956 -5.43128 0.00871152 -3.15222 -0.0045412 -0.0023397 0.00332764 +EDGE3 1905 1956 -5.90631 5.94665 -3.23051 -0.00299968 -0.00395425 0.123487 +EDGE3 1906 1955 -5.69797 -5.96699 -3.09568 -0.00650241 -0.00756336 -0.131506 +EDGE3 1907 1957 -5.41931 -0.00557384 -3.1389 -0.0127214 0.00485097 -0.00732458 +EDGE3 1906 1957 -5.91347 5.95343 -3.22571 0.00138954 -0.00508784 0.122327 +EDGE3 1907 1956 -5.69957 -5.9499 -3.07238 0.0050695 -0.0027827 -0.134899 +EDGE3 1908 1958 -5.45633 0.0119737 -3.16457 0.0181138 0.00275565 -0.0032894 +EDGE3 1907 1958 -5.91871 5.92302 -3.20011 -0.00220222 -0.000995355 0.128028 +EDGE3 1908 1957 -5.70374 -5.93753 -3.09047 0.00433953 0.00191999 -0.112961 +EDGE3 1909 1959 -5.43794 0.00255173 -3.12671 0.00169914 0.00327618 0.00143381 +EDGE3 1908 1959 -5.91487 5.90552 -3.21657 -0.0019754 0.00129584 0.129298 +EDGE3 1909 1958 -5.70787 -5.93481 -3.07223 0.00896748 -0.00820647 -0.13072 +EDGE3 1910 1960 -5.45253 0.00299423 -3.12474 0.00722001 0.00176273 -0.00083542 +EDGE3 1909 1960 -5.92128 5.90153 -3.21425 0.00767992 -0.00274562 0.128302 +EDGE3 1910 1959 -5.70742 -5.91613 -3.06455 0.00616479 -0.00631238 -0.12793 +EDGE3 1911 1961 -5.44458 -0.00107663 -3.142 -0.00786885 0.00688707 0.00658756 +EDGE3 1910 1961 -5.93376 5.88349 -3.17342 0.0111102 0.00311372 0.12621 +EDGE3 1911 1960 -5.72226 -5.90948 -3.06114 0.0110804 -0.000140461 -0.123374 +EDGE3 1912 1962 -5.45094 -0.00970238 -3.12651 -0.011332 -0.00322675 -0.00543351 +EDGE3 1911 1962 -5.90333 5.87903 -3.17783 0.00807875 0.0014455 0.133496 +EDGE3 1912 1961 -5.7152 -5.90113 -3.05341 -0.000771196 0.00342868 -0.127841 +EDGE3 1913 1963 -5.45458 -0.0108798 -3.11279 -0.00207864 0.0010523 0.00111623 +EDGE3 1912 1963 -5.92005 5.85179 -3.18131 -0.000944133 -0.000473549 0.1245 +EDGE3 1913 1962 -5.71749 -5.87549 -3.04925 0.0152772 -0.00274506 -0.126617 +EDGE3 1914 1964 -5.45486 0.0139235 -3.09703 0.00791159 -0.00682328 -0.00499117 +EDGE3 1913 1964 -5.92801 5.84591 -3.16384 -0.0028415 0.00221034 0.122493 +EDGE3 1914 1963 -5.7099 -5.86629 -3.03149 -0.00664256 -0.00755185 -0.124237 +EDGE3 1915 1965 -5.45465 -0.00518927 -3.09157 0.00402723 0.00513008 0.000818003 +EDGE3 1914 1965 -5.9486 5.81957 -3.16872 0.00816466 -0.000146956 0.12543 +EDGE3 1915 1964 -5.73817 -5.84353 -3.04801 0.00321765 0.00421407 -0.126767 +EDGE3 1916 1966 -5.46059 -0.00275226 -3.07958 -0.0134542 0.00801459 -0.0060315 +EDGE3 1915 1966 -5.93285 5.83272 -3.14942 0.0107932 0.00480811 0.121129 +EDGE3 1916 1965 -5.7283 -5.83024 -3.0416 -0.00678177 0.000375403 -0.123407 +EDGE3 1917 1967 -5.47525 0.00102524 -3.08743 0.00147318 8.50273e-05 0.00990075 +EDGE3 1916 1967 -5.95191 5.80714 -3.15122 -0.00863514 0.00559517 0.138128 +EDGE3 1917 1966 -5.73631 -5.82201 -3.01779 0.00481043 -0.0105813 -0.138089 +EDGE3 1918 1968 -5.46687 0.0129975 -3.0764 0.00112787 0.00416425 -0.00597787 +EDGE3 1917 1968 -5.93639 5.79409 -3.12968 0.000345783 0.0037258 0.12408 +EDGE3 1918 1967 -5.7103 -5.81196 -3.0143 0.0013524 -0.00193262 -0.133577 +EDGE3 1919 1969 -5.47851 0.00531679 -3.08727 -0.00115575 0.00299742 -0.00741325 +EDGE3 1918 1969 -5.94807 5.79671 -3.12893 0.00132322 0.00553222 0.119934 +EDGE3 1919 1968 -5.75164 -5.78267 -3.00684 -0.00500797 0.00385851 -0.128026 +EDGE3 1920 1970 -5.51027 0.00290657 -3.06881 0.00177696 -0.00481297 -0.00188406 +EDGE3 1919 1970 -5.95473 5.75885 -3.10824 -0.00776289 0.00768938 0.130911 +EDGE3 1920 1969 -5.74765 -5.78063 -3.00592 0.000494625 0.00218535 -0.118755 +EDGE3 1921 1971 -5.48623 0.0127142 -3.05473 -0.000712989 0.00595857 0.00520224 +EDGE3 1920 1971 -5.96173 5.74132 -3.12812 0.00672913 0.00156664 0.126894 +EDGE3 1921 1970 -5.74785 -5.75423 -2.9902 -0.00442636 0.00591841 -0.124254 +EDGE3 1922 1972 -5.47486 -0.00957271 -3.03015 0.00575038 0.00956175 0.00901711 +EDGE3 1921 1972 -5.96861 5.7276 -3.10775 0.00677739 -0.00107328 0.119132 +EDGE3 1922 1971 -5.75517 -5.75839 -2.99568 -0.00219476 0.00199698 -0.127549 +EDGE3 1923 1973 -5.505 -0.00324469 -3.04968 0.00360502 -0.00987679 -0.00702848 +EDGE3 1922 1973 -5.96631 5.73624 -3.10643 -0.0020861 -0.00207337 0.132013 +EDGE3 1923 1972 -5.74023 -5.71548 -2.99698 0.00335579 0.00137074 -0.124558 +EDGE3 1924 1974 -5.51265 0.00504605 -3.03273 0.00297301 0.000267571 -0.00238564 +EDGE3 1923 1974 -5.96351 5.71065 -3.11396 0.00538354 -0.00737199 0.124121 +EDGE3 1924 1973 -5.7536 -5.71326 -2.96847 0.00353678 0.0102409 -0.129999 +EDGE3 1925 1975 -5.49935 0.00976312 -3.04737 -3.64189e-05 0.00117017 -0.000540121 +EDGE3 1924 1975 -5.97896 5.67893 -3.09727 -0.0037038 0.00462302 0.124485 +EDGE3 1925 1974 -5.7542 -5.70214 -2.96842 0.0102969 0.00325885 -0.125939 +EDGE3 1926 1976 -5.51296 0.0058147 -3.02713 0.000238775 -0.000365179 -0.00342774 +EDGE3 1925 1976 -5.96709 5.67253 -3.08881 -0.00493901 -0.0139938 0.129311 +EDGE3 1926 1975 -5.73122 -5.6896 -2.97701 0.00409519 0.000105824 -0.134319 +EDGE3 1927 1977 -5.53409 0.00925834 -3.01108 -0.00234978 -0.00809264 -0.00670391 +EDGE3 1926 1977 -5.98768 5.66112 -3.07957 0.00207868 -0.00428169 0.118597 +EDGE3 1927 1976 -5.76025 -5.66852 -2.9705 0.00425601 -0.00519793 -0.124708 +EDGE3 1928 1978 -5.49545 -0.0113442 -2.97665 0.00347308 0.000693838 -0.00418668 +EDGE3 1927 1978 -5.95456 5.6351 -3.06152 -0.00627341 0.000832713 0.130825 +EDGE3 1928 1977 -5.74925 -5.6621 -2.93415 -0.00152813 -0.00691283 -0.122927 +EDGE3 1929 1979 -5.52943 0.0037856 -3.00264 -0.0031097 -0.00164873 -0.000470783 +EDGE3 1928 1979 -5.99905 5.64829 -3.0759 -0.0013635 0.00264902 0.112056 +EDGE3 1929 1978 -5.7643 -5.63266 -2.94203 0.00087833 0.00022573 -0.128858 +EDGE3 1930 1980 -5.52834 0.00646121 -2.99251 -0.00105196 -0.00491989 0.00375517 +EDGE3 1929 1980 -5.98436 5.61263 -3.06471 -0.00595355 -0.00497491 0.133621 +EDGE3 1930 1979 -5.77351 -5.65358 -2.94399 0.011942 0.00784394 -0.12568 +EDGE3 1931 1981 -5.53466 0.0108668 -2.98951 0.00335638 -0.00151867 0.00626584 +EDGE3 1930 1981 -5.97143 5.61538 -3.05299 -0.00268779 0.00806028 0.12164 +EDGE3 1931 1980 -5.76763 -5.60878 -2.92867 -0.000692859 0.00759049 -0.130414 +EDGE3 1932 1982 -5.54389 0.0158913 -2.97691 -0.00275903 -0.0020458 0.00791519 +EDGE3 1931 1982 -5.98414 5.61229 -3.04283 -0.00778799 0.0019244 0.126726 +EDGE3 1932 1981 -5.7656 -5.60498 -2.90806 -0.00058178 -7.96522e-05 -0.117146 +EDGE3 1933 1983 -5.52911 0.00249384 -2.9692 0.00255532 0.00426569 0.0105989 +EDGE3 1932 1983 -5.99046 5.57183 -3.04143 0.0114317 0.00166349 0.12025 +EDGE3 1933 1982 -5.78678 -5.60859 -2.91803 -0.00619448 0.000866437 -0.118936 +EDGE3 1934 1984 -5.5434 0.0080529 -2.96469 -0.00153978 0.00478685 -0.00970984 +EDGE3 1933 1984 -6.0028 5.56902 -3.02333 -0.0102068 0.00696758 0.12744 +EDGE3 1934 1983 -5.77199 -5.58286 -2.91125 -0.00257946 0.00054549 -0.126268 +EDGE3 1935 1985 -5.55857 -0.00577557 -2.96556 0.00483907 -0.00353712 -0.000410494 +EDGE3 1934 1985 -6.00934 5.53947 -3.01819 -0.00800605 0.00262047 0.128033 +EDGE3 1935 1984 -5.79441 -5.57675 -2.90252 -0.00133558 -0.000237224 -0.131593 +EDGE3 1936 1986 -5.54686 0.0023144 -2.94801 0.00597871 3.93326e-05 0.00112469 +EDGE3 1935 1986 -6.0051 5.54155 -3.00839 -0.00116882 -0.00665964 0.130864 +EDGE3 1936 1985 -5.78159 -5.54734 -2.89328 0.00478137 -0.00117958 -0.130937 +EDGE3 1937 1987 -5.54665 -0.011941 -2.92994 -0.00724633 -0.00108401 -0.0052027 +EDGE3 1936 1987 -6.01735 5.52662 -3.00387 0.00842214 0.00210134 0.116253 +EDGE3 1937 1986 -5.77099 -5.53528 -2.8886 0.000346885 0.00526133 -0.124321 +EDGE3 1938 1988 -5.56683 -0.00291494 -2.9358 -0.000712875 -0.00129538 -0.000686411 +EDGE3 1937 1988 -6.01441 5.51297 -3.00172 0.00520635 0.00497543 0.129399 +EDGE3 1938 1987 -5.79441 -5.50623 -2.88102 -0.0047978 -0.00417152 -0.134286 +EDGE3 1939 1989 -5.55124 -0.0158818 -2.93374 0.000801164 -0.00105943 -0.00579888 +EDGE3 1938 1989 -6.0063 5.50203 -2.98735 -0.0063503 0.00427412 0.114408 +EDGE3 1939 1988 -5.79818 -5.52221 -2.88128 0.00701604 -0.00536374 -0.112867 +EDGE3 1940 1990 -5.57132 0.0116076 -2.92598 0.00380591 -0.00131419 0.00322591 +EDGE3 1939 1990 -6.00843 5.47458 -2.98888 -0.000492734 0.00235777 0.126978 +EDGE3 1940 1989 -5.78457 -5.49092 -2.88974 0.000228448 0.00680623 -0.126548 +EDGE3 1941 1991 -5.56991 -0.00558997 -2.89809 0.00242658 0.00931747 0.00204082 +EDGE3 1940 1991 -5.99684 5.45655 -2.98526 -0.00137462 -0.00527492 0.131652 +EDGE3 1941 1990 -5.79629 -5.47263 -2.85105 0.00595228 -0.00142078 -0.12293 +EDGE3 1942 1992 -5.59152 -0.0212325 -2.90127 -0.00540962 0.00597246 0.00312764 +EDGE3 1941 1992 -6.02367 5.44705 -2.98275 0.00135644 0.00170721 0.122284 +EDGE3 1942 1991 -5.79717 -5.44616 -2.8524 0.00486424 0.00873439 -0.1335 +EDGE3 1943 1993 -5.5772 -0.010063 -2.88379 -0.00103114 -0.00478939 -0.00587242 +EDGE3 1942 1993 -6.01119 5.43886 -2.97587 -0.00725017 -0.00319134 0.126522 +EDGE3 1943 1992 -5.79927 -5.47078 -2.83014 0.00352528 0.00413822 -0.125509 +EDGE3 1944 1994 -5.57365 0.000848455 -2.88549 -0.001073 0.00572914 -0.0008407 +EDGE3 1943 1994 -6.02653 5.41374 -2.9452 -0.000383602 -0.00795551 0.12434 +EDGE3 1944 1993 -5.80088 -5.41726 -2.85127 0.0114619 -0.00490873 -0.125047 +EDGE3 1945 1995 -5.58552 0.00101109 -2.90024 -0.00814831 0.0039062 -0.00378408 +EDGE3 1944 1995 -6.01961 5.40448 -2.95355 0.00527659 0.00264058 0.13221 +EDGE3 1945 1994 -5.7977 -5.4279 -2.85378 -0.0101286 0.00276164 -0.123742 +EDGE3 1946 1996 -5.57451 -0.00145722 -2.8682 0.00169367 -0.0146546 -0.00380074 +EDGE3 1945 1996 -6.03607 5.38742 -2.9358 0.00149363 -0.00246134 0.129947 +EDGE3 1946 1995 -5.80325 -5.41852 -2.81974 0.0107271 -0.00925749 -0.122772 +EDGE3 1947 1997 -5.59283 -0.0117238 -2.87841 -0.000609928 -0.00221692 0.00111616 +EDGE3 1946 1997 -6.03117 5.36613 -2.93584 0.00889473 0.00301499 0.122241 +EDGE3 1947 1996 -5.80672 -5.37803 -2.83131 -0.0062877 -0.0032303 -0.126607 +EDGE3 1948 1998 -5.58457 -0.00119354 -2.87158 -0.00559931 -0.00844645 -0.00423722 +EDGE3 1947 1998 -6.03402 5.37986 -2.93836 -0.00682208 -0.00144857 0.11827 +EDGE3 1948 1997 -5.82088 -5.38313 -2.80311 0.000691188 0.00215266 -0.122895 +EDGE3 1949 1999 -5.59071 0.00667578 -2.86478 8.55629e-05 0.00595285 -0.0049736 +EDGE3 1948 1999 -6.02021 5.33921 -2.92573 -0.00142202 -0.00573423 0.127055 +EDGE3 1949 1998 -5.81159 -5.35273 -2.80336 0.000684082 0.0035971 -0.121843 +EDGE3 1950 2000 -5.59575 -0.00419579 -2.86647 -0.00277985 0.0104589 -0.00212302 +EDGE3 1949 2000 -6.0742 5.32421 -2.89755 0.0123511 0.00706643 0.125618 +EDGE3 1950 1999 -5.81671 -5.34966 -2.79616 0.00230823 -0.00228506 -0.126171 +EDGE3 1951 2001 -5.60296 -0.00817804 -2.8594 0.000276944 -0.000886763 0.0110153 +EDGE3 1950 2001 -6.05539 5.32921 -2.90149 -0.00189942 -0.00572901 0.119612 +EDGE3 1951 2000 -5.81911 -5.34241 -2.79742 -0.000302118 0.00617901 -0.122047 +EDGE3 1952 2002 -5.61285 0.00273397 -2.85226 -0.00131322 0.00654866 0.00451317 +EDGE3 1951 2002 -6.04454 5.31233 -2.90912 -0.00676358 -0.00176541 0.123367 +EDGE3 1952 2001 -5.81987 -5.29939 -2.7974 0.00237527 0.0029512 -0.127436 +EDGE3 1953 2003 -5.61281 0.0173624 -2.83283 -0.00821729 0.00231243 -0.00198992 +EDGE3 1952 2003 -6.0442 5.28225 -2.88559 0.00479039 -0.00290219 0.12475 +EDGE3 1953 2002 -5.84024 -5.31216 -2.76189 0.00841298 -0.00132699 -0.12934 +EDGE3 1954 2004 -5.60898 -0.00274502 -2.8168 -0.00367854 -0.00114419 0.00228453 +EDGE3 1953 2004 -6.04515 5.27668 -2.88639 0.00377854 -0.00605849 0.118488 +EDGE3 1954 2003 -5.81976 -5.29148 -2.78273 0.00333521 -0.000956545 -0.131773 +EDGE3 1955 2005 -5.61379 0.00407275 -2.82358 -0.00383064 0.00663643 -0.00336601 +EDGE3 1954 2005 -6.06558 5.26941 -2.8788 0.00720361 -0.00582111 0.123006 +EDGE3 1955 2004 -5.82779 -5.2801 -2.76155 -0.000260862 0.00568802 -0.137603 +EDGE3 1956 2006 -5.6295 -0.00297196 -2.80581 -0.00538486 0.00249065 0.00309432 +EDGE3 1955 2006 -6.0489 5.24933 -2.85136 0.00451571 -0.00804957 0.120522 +EDGE3 1956 2005 -5.83137 -5.26182 -2.75858 -0.00344215 -0.00685491 -0.121845 +EDGE3 1957 2007 -5.61548 0.00536062 -2.80103 0.00297612 -0.00503937 0.00470988 +EDGE3 1956 2007 -6.06453 5.24294 -2.8512 -0.000956403 -0.00108455 0.131191 +EDGE3 1957 2006 -5.85078 -5.26019 -2.75804 -0.00825878 -0.00388195 -0.131439 +EDGE3 1958 2008 -5.62227 0.0155275 -2.79241 0.000697699 -0.000490867 0.00176388 +EDGE3 1957 2008 -6.05818 5.22696 -2.86052 0.00365555 -0.000990128 0.124371 +EDGE3 1958 2007 -5.83188 -5.21839 -2.74016 -0.00317899 0.00187072 -0.12843 +EDGE3 1959 2009 -5.6453 0.00740263 -2.78745 0.00713127 0.00674665 0.00755264 +EDGE3 1958 2009 -6.06069 5.20371 -2.84382 0.00427806 -0.00211225 0.120322 +EDGE3 1959 2008 -5.82827 -5.22266 -2.74746 0.00499369 0.00577802 -0.115161 +EDGE3 1960 2010 -5.64157 0.0181014 -2.78037 -0.00184412 -0.00143602 -0.00150876 +EDGE3 1959 2010 -6.07768 5.19253 -2.83891 -0.00825649 -0.00219315 0.130249 +EDGE3 1960 2009 -5.84075 -5.21011 -2.71681 0.00608648 0.00230065 -0.13551 +EDGE3 1961 2011 -5.62202 0.00423525 -2.7681 0.00262469 -0.00404198 0.0140314 +EDGE3 1960 2011 -6.07257 5.18361 -2.82335 0.00486628 0.0103289 0.123439 +EDGE3 1961 2010 -5.85159 -5.20161 -2.70799 0.00840214 2.97394e-05 -0.139751 +EDGE3 1962 2012 -5.63987 0.00177652 -2.77025 0.00348143 -0.00461863 0.00311556 +EDGE3 1961 2012 -6.0871 5.15877 -2.80454 -0.000799931 0.00151283 0.128089 +EDGE3 1962 2011 -5.84812 -5.17487 -2.72569 -0.00881248 -0.0052736 -0.120447 +EDGE3 1963 2013 -5.63908 0.00053293 -2.75841 0.000588165 0.00402461 0.00584897 +EDGE3 1962 2013 -6.0823 5.15393 -2.81107 -0.00543668 0.00423426 0.127617 +EDGE3 1963 2012 -5.85326 -5.15448 -2.6814 0.00442265 -0.00197515 -0.129062 +EDGE3 1964 2014 -5.65934 0.00807446 -2.75546 -0.00137949 0.00875705 0.00398367 +EDGE3 1963 2014 -6.08205 5.12148 -2.8239 -0.000365711 -0.000260473 0.136815 +EDGE3 1965 2015 -5.65678 -0.0146728 -2.73639 -0.00254799 -0.0048732 0.00479912 +EDGE3 1964 2013 -5.85473 -5.14415 -2.70807 0.00722985 0.00339841 -0.123566 +EDGE3 1964 2015 -6.07785 5.12658 -2.79758 -0.00139057 -0.0034229 0.12108 +EDGE3 1965 2014 -5.85575 -5.12004 -2.68467 -0.0164985 0.0066618 -0.1217 +EDGE3 1966 2016 -5.65072 0.0169404 -2.72819 -0.00259626 0.00257382 0.00128452 +EDGE3 1965 2016 -6.08283 5.10486 -2.80138 -8.07433e-05 -0.00398571 0.128943 +EDGE3 1966 2015 -5.85844 -5.11895 -2.70445 0.00431656 0.00286175 -0.137684 +EDGE3 1967 2017 -5.64567 -0.00431639 -2.72747 -0.00299496 0.0081383 -0.00585009 +EDGE3 1966 2017 -6.08822 5.07109 -2.79196 0.00349544 0.00207464 0.134647 +EDGE3 1967 2016 -5.86688 -5.11326 -2.6985 0.00429477 -0.00591933 -0.128054 +EDGE3 1968 2018 -5.65801 0.0206301 -2.73953 -0.00527999 -0.000269626 -0.00189452 +EDGE3 1967 2018 -6.10321 5.06804 -2.78564 -0.000658319 0.00024317 0.123474 +EDGE3 1968 2017 -5.84895 -5.06092 -2.67389 0.00612391 0.000819214 -0.112843 +EDGE3 1969 2019 -5.65846 0.00559005 -2.70045 0.000417581 0.00408351 -0.0006966 +EDGE3 1968 2019 -6.08899 5.06229 -2.78422 0.00282868 0.00121901 0.130076 +EDGE3 1969 2018 -5.86343 -5.06675 -2.6634 -0.00217478 0.0044978 -0.121873 +EDGE3 1970 2020 -5.67546 0.0152022 -2.71622 -0.00808119 -0.00293761 0.00241239 +EDGE3 1969 2020 -6.10034 5.03042 -2.77528 0.00139948 0.0018802 0.125519 +EDGE3 1970 2019 -5.88227 -5.06667 -2.66501 0.00243645 -0.0024782 -0.124427 +EDGE3 1971 2021 -5.66792 -0.00371838 -2.70377 -0.00293968 -0.000444173 0.00155232 +EDGE3 1970 2021 -6.09984 5.04601 -2.76069 -0.00472765 0.00851885 0.119881 +EDGE3 1971 2020 -5.8707 -5.05888 -2.64735 -0.0049322 0.00401403 -0.123807 +EDGE3 1972 2022 -5.66352 -0.00179885 -2.70368 0.00346185 -9.73194e-05 -0.00571407 +EDGE3 1971 2022 -6.09477 5.03497 -2.76518 0.00128165 -0.00177571 0.118167 +EDGE3 1972 2021 -5.87806 -5.05371 -2.62816 0.00381303 0.00369958 -0.118824 +EDGE3 1973 2023 -5.67573 -0.0167079 -2.70349 0.00113967 0.00291716 -0.00290714 +EDGE3 1972 2023 -6.11164 5.01021 -2.7475 -0.00477598 -0.00138039 0.12133 +EDGE3 1973 2022 -5.87426 -5.02266 -2.65041 0.00765128 0.00101388 -0.129682 +EDGE3 1974 2024 -5.67797 -0.00440572 -2.68056 0.0069377 0.00706319 -0.00331808 +EDGE3 1973 2024 -6.11386 4.98268 -2.72325 0.00356497 0.00103656 0.134316 +EDGE3 1974 2023 -5.86791 -5.00645 -2.63004 0.00499318 0.00397367 -0.123661 +EDGE3 1975 2025 -5.69194 -0.00939471 -2.66728 -0.00371873 0.00491463 -0.00290824 +EDGE3 1974 2025 -6.10495 4.98567 -2.72957 -0.00874588 0.00174585 0.127264 +EDGE3 1975 2024 -5.87097 -4.97912 -2.62542 0.00586282 0.00449985 -0.122856 +EDGE3 1976 2026 -5.69275 0.00175766 -2.64297 -0.00659111 -0.00304246 -0.00342775 +EDGE3 1975 2026 -6.11354 4.98457 -2.69983 -0.011482 -0.00538869 0.128734 +EDGE3 1976 2025 -5.88145 -4.99451 -2.6125 -0.00802617 -0.000498878 -0.126156 +EDGE3 1977 2027 -5.68552 -0.00259463 -2.65417 -0.000895117 -0.00917468 0.00466201 +EDGE3 1976 2027 -6.10601 4.94769 -2.71653 0.000402919 0.00629842 0.12919 +EDGE3 1977 2026 -5.88762 -4.97776 -2.60792 -0.00789496 0.00442893 -0.127865 +EDGE3 1978 2028 -5.68832 -0.0120616 -2.66402 -0.00253004 0.000279988 0.00390043 +EDGE3 1977 2028 -6.12622 4.93498 -2.71018 0.00480295 0.00156111 0.126563 +EDGE3 1978 2027 -5.87971 -4.97422 -2.60538 -0.00113797 0.00451869 -0.122012 +EDGE3 1979 2029 -5.68937 -0.00483494 -2.65422 0.0019051 0.00022987 0.000628138 +EDGE3 1978 2029 -6.0981 4.92902 -2.71323 0.00349942 -0.00319367 0.122731 +EDGE3 1979 2028 -5.89997 -4.95356 -2.60002 0.00104094 -0.0029203 -0.122893 +EDGE3 1980 2030 -5.70644 0.00981718 -2.63796 -0.000810061 0.000815083 0.00394178 +EDGE3 1979 2030 -6.11012 4.91604 -2.68577 0.000373158 -0.00146418 0.12864 +EDGE3 1980 2029 -5.89608 -4.91491 -2.58249 0.00716838 0.000627993 -0.126979 +EDGE3 1981 2031 -5.70029 0.0103036 -2.61469 -0.00812967 -0.0105987 0.000201646 +EDGE3 1980 2031 -6.12635 4.89014 -2.69433 0.00496996 0.00453455 0.129435 +EDGE3 1981 2030 -5.90683 -4.90595 -2.58374 -0.00883008 0.00295164 -0.128402 +EDGE3 1982 2032 -5.71383 -0.00508804 -2.61098 -0.00172683 -0.00616701 -0.00188828 +EDGE3 1981 2032 -6.12548 4.87477 -2.66559 -0.0019092 -0.0121391 0.123419 +EDGE3 1982 2031 -5.87399 -4.87441 -2.56641 0.000194926 -0.00365293 -0.12622 +EDGE3 1983 2033 -5.70435 -4.68006e-05 -2.61322 -0.00119224 -0.00427238 -0.000459402 +EDGE3 1982 2033 -6.14499 4.86172 -2.69185 0.00258962 0.00167336 0.119678 +EDGE3 1983 2032 -5.88933 -4.87997 -2.57352 0.0136186 -0.00053469 -0.113947 +EDGE3 1984 2034 -5.70866 0.00740743 -2.6169 0.0070403 -0.00740498 -0.00426495 +EDGE3 1983 2034 -6.12992 4.8486 -2.67041 0.000613673 -0.00484777 0.123082 +EDGE3 1984 2033 -5.89246 -4.8649 -2.55875 -0.00150449 -0.000601549 -0.118692 +EDGE3 1985 2035 -5.72381 0.00196836 -2.6104 0.00474132 0.00369973 -0.00928139 +EDGE3 1984 2035 -6.14261 4.82665 -2.65943 -0.00386675 0.000172735 0.117963 +EDGE3 1985 2034 -5.91073 -4.84735 -2.54636 -0.00497801 0.00234227 -0.12809 +EDGE3 1985 2036 -6.11982 4.80201 -2.66184 -0.00324819 0.00863909 0.12945 +EDGE3 1986 2036 -5.72677 0.00382911 -2.59004 0.00980639 0.0010069 0.0089004 +EDGE3 1987 2037 -5.729 0.0125778 -2.60432 -0.00461108 -0.000919019 -0.00405932 +EDGE3 1986 2035 -5.91921 -4.82525 -2.55333 -0.0037187 0.00610245 -0.123571 +EDGE3 1986 2037 -6.14308 4.79213 -2.6394 -0.00708418 0.000286545 0.127403 +EDGE3 1987 2036 -5.90948 -4.81843 -2.53106 -0.00374852 0.0136236 -0.130216 +EDGE3 1988 2038 -5.72723 -0.012184 -2.58184 0.00280776 -0.00303138 0.00678438 +EDGE3 1987 2038 -6.13312 4.7865 -2.65133 -0.00370447 0.000732884 0.125371 +EDGE3 1988 2037 -5.88902 -4.80056 -2.54457 -0.000314103 0.00249991 -0.126326 +EDGE3 1989 2039 -5.71025 -0.00967135 -2.5907 0.00537582 1.53546e-05 -0.00146584 +EDGE3 1988 2039 -6.153 4.76545 -2.65028 0.0117102 0.00144592 0.128812 +EDGE3 1989 2038 -5.8993 -4.80011 -2.5341 0.00288866 0.0063646 -0.119684 +EDGE3 1990 2040 -5.73889 -0.00119034 -2.56429 -0.00109989 -0.00315108 0.00031357 +EDGE3 1989 2040 -6.15324 4.77179 -2.64271 -0.001378 -0.00117353 0.124713 +EDGE3 1990 2039 -5.92804 -4.7756 -2.51318 -0.000644632 0.00395925 -0.125373 +EDGE3 1991 2041 -5.71671 4.96791e-05 -2.56081 -0.00240224 0.00493047 -0.000233993 +EDGE3 1990 2041 -6.13659 4.7519 -2.61667 -0.00117809 -0.00589109 0.124796 +EDGE3 1991 2040 -5.91479 -4.76916 -2.52589 -0.00522813 -1.21103e-05 -0.123421 +EDGE3 1992 2042 -5.741 0.0163824 -2.53424 -0.00332111 0.00513903 -0.00328601 +EDGE3 1991 2042 -6.14323 4.72251 -2.59834 -0.012849 0.00702589 0.1204 +EDGE3 1992 2041 -5.91697 -4.74255 -2.49408 0.00197826 0.00233048 -0.135124 +EDGE3 1993 2043 -5.74865 0.00741669 -2.53799 -0.00231165 -0.00337837 0.00893604 +EDGE3 1992 2043 -6.15616 4.70534 -2.60166 -0.0062415 0.00222547 0.127571 +EDGE3 1993 2042 -5.9251 -4.72891 -2.48772 -0.000202461 0.00309071 -0.127355 +EDGE3 1994 2044 -5.73641 -0.00432517 -2.55032 -0.00244914 -0.00071224 -0.00606833 +EDGE3 1993 2044 -6.14334 4.6887 -2.58314 -0.00048312 0.00916664 0.136056 +EDGE3 1994 2043 -5.93669 -4.72724 -2.49448 -0.00379939 -0.00258039 -0.125835 +EDGE3 1995 2045 -5.76333 -0.00576178 -2.53612 0.0034264 0.00257061 -0.00514583 +EDGE3 1994 2045 -6.17376 4.67516 -2.59567 -0.00447444 0.00525539 0.123384 +EDGE3 1995 2044 -5.91971 -4.69424 -2.47222 -0.00527692 -0.00213859 -0.124652 +EDGE3 1996 2046 -5.75783 0.00566603 -2.5296 0.00286347 -1.47955e-05 -0.00253179 +EDGE3 1995 2046 -6.15345 4.6678 -2.56932 0.00390513 0.00643812 0.131291 +EDGE3 1996 2045 -5.92701 -4.67611 -2.47095 -0.00161134 0.000700915 -0.120453 +EDGE3 1997 2047 -5.74533 0.00651527 -2.52244 -0.00324859 0.00305536 -0.00550445 +EDGE3 1996 2047 -6.15972 4.65363 -2.56111 -0.00111321 -0.00352066 0.131328 +EDGE3 1997 2046 -5.90996 -4.66918 -2.46934 0.00750882 0.00411914 -0.125018 +EDGE3 1998 2048 -5.74915 0.00115262 -2.52889 0.000972271 -0.000143849 0.00251976 +EDGE3 1997 2048 -6.18446 4.64395 -2.57079 0.00187662 -0.00478119 0.118365 +EDGE3 1998 2047 -5.9519 -4.66086 -2.44759 -0.00208003 -0.00851716 -0.13098 +EDGE3 1999 2049 -5.76126 -0.0108822 -2.50516 -0.00467626 -0.00446563 -0.00804558 +EDGE3 1998 2049 -6.15605 4.6253 -2.56056 0.00279508 -0.0109602 0.134323 +EDGE3 1999 2048 -5.94408 -4.65923 -2.45192 0.000883096 0.00140328 -0.123139 +EDGE3 2000 2050 -5.74839 -0.00734357 -2.49863 0.000311057 -0.00142417 -0.00377704 +EDGE3 1999 2050 -6.15495 4.61349 -2.5414 -0.000181217 -0.00203306 0.129037 +EDGE3 2000 2049 -5.9317 -4.64752 -2.44503 0.00901745 0.0017234 -0.118038 +EDGE3 2001 2051 -5.75976 -0.00171117 -2.47989 -0.00792534 -0.00413709 -0.00781739 +EDGE3 2000 2051 -6.18659 4.58175 -2.54779 -0.0049066 0.00259802 0.132815 +EDGE3 2001 2050 -5.9428 -4.61092 -2.4395 -0.00525132 -0.000677051 -0.127397 +EDGE3 2002 2052 -5.76636 -0.00599688 -2.48583 -0.00468483 0.00396651 -0.0103127 +EDGE3 2001 2052 -6.17512 4.57127 -2.52633 -0.00953566 -0.00267424 0.127105 +EDGE3 2002 2051 -5.94168 -4.59943 -2.4424 0.0128335 -0.00304354 -0.120298 +EDGE3 2003 2053 -5.79252 0.00870577 -2.47847 0.00523746 0.00536477 -0.00327143 +EDGE3 2002 2053 -6.17521 4.5837 -2.53395 0.00523524 -0.00324907 0.121779 +EDGE3 2003 2052 -5.96882 -4.58883 -2.41945 -0.00478965 -0.00231544 -0.123808 +EDGE3 2004 2054 -5.7833 0.00424501 -2.44278 0.00433057 0.000918187 0.00124686 +EDGE3 2003 2054 -6.17929 4.54089 -2.51051 -0.00260013 0.00243351 0.117058 +EDGE3 2004 2053 -5.94159 -4.56642 -2.42422 -0.0102416 0.0140781 -0.130452 +EDGE3 2005 2055 -5.7833 0.0107374 -2.45063 -0.00533231 -0.00684012 -0.000816218 +EDGE3 2004 2055 -6.19837 4.55516 -2.48559 0.000204753 -0.000251432 0.127914 +EDGE3 2005 2054 -5.95925 -4.54763 -2.41681 0.00382441 0.000949968 -0.129762 +EDGE3 2006 2056 -5.7822 0.00724095 -2.46771 0.000405986 -0.00720977 0.00958064 +EDGE3 2005 2056 -6.19318 4.54003 -2.51721 -0.00390878 -0.00744035 0.1302 +EDGE3 2006 2055 -5.94797 -4.52302 -2.40885 -0.00223352 -0.000435366 -0.127858 +EDGE3 2007 2057 -5.76886 -0.010995 -2.45151 -0.00409119 0.00292958 0.000803437 +EDGE3 2006 2057 -6.17297 4.5262 -2.49637 -0.000106723 0.000946703 0.125539 +EDGE3 2007 2056 -5.96426 -4.53065 -2.40055 0.00263694 -0.0034985 -0.131254 +EDGE3 2008 2058 -5.77018 -0.0204112 -2.4319 0.000360716 0.000153387 -0.0079421 +EDGE3 2007 2058 -6.19358 4.49765 -2.4925 -0.00447799 0.00287667 0.113149 +EDGE3 2008 2057 -5.95241 -4.51212 -2.39668 0.00188614 0.000221794 -0.128015 +EDGE3 2009 2059 -5.79377 -0.00355615 -2.43807 0.00422429 -0.00966115 0.00691968 +EDGE3 2008 2059 -6.20564 4.46627 -2.49273 0.00493664 0.0116841 0.139501 +EDGE3 2009 2058 -5.95562 -4.4939 -2.39892 -0.00361686 0.00359153 -0.125469 +EDGE3 2010 2060 -5.79519 0.00593328 -2.40915 -0.00381593 -0.0016928 0.00588013 +EDGE3 2009 2060 -6.18672 4.46745 -2.47876 0.000144335 0.00164268 0.120873 +EDGE3 2010 2059 -5.95643 -4.48242 -2.37213 0.0043481 0.00783785 -0.12656 +EDGE3 2011 2061 -5.8084 0.00483225 -2.41618 -0.00410435 0.00912598 -0.00298907 +EDGE3 2010 2061 -6.1939 4.47309 -2.48134 -0.00345444 0.00244604 0.125125 +EDGE3 2011 2060 -5.95421 -4.47608 -2.36864 0.00393282 -0.00115712 -0.125808 +EDGE3 2012 2062 -5.7916 -0.0103155 -2.40741 0.00440796 -0.0042292 0.00732876 +EDGE3 2011 2062 -6.20243 4.44467 -2.44085 0.00545389 -0.00251864 0.129854 +EDGE3 2012 2061 -5.95978 -4.46504 -2.36904 -0.00628232 0.00605086 -0.134242 +EDGE3 2013 2063 -5.80251 -0.00230012 -2.40784 0.00524565 0.00500367 -0.00566374 +EDGE3 2012 2063 -6.18106 4.43892 -2.45672 -0.00168207 0.00448498 0.11631 +EDGE3 2013 2062 -5.95827 -4.43563 -2.35991 -0.00322014 0.00554915 -0.128251 +EDGE3 2014 2064 -5.80304 0.00671367 -2.40861 0.000872453 -0.000913993 0.00346853 +EDGE3 2013 2064 -6.19008 4.41356 -2.43988 0.00097156 0.000918992 0.124359 +EDGE3 2014 2063 -5.96061 -4.43742 -2.34713 -0.00370086 0.00230485 -0.137001 +EDGE3 2015 2065 -5.81365 0.0123481 -2.38514 0.00597459 0.00638675 0.00180554 +EDGE3 2014 2065 -6.18997 4.40277 -2.43678 0.00531478 -0.00600919 0.137856 +EDGE3 2015 2064 -5.97621 -4.40493 -2.35252 0.00517561 -0.00258623 -0.13144 +EDGE3 2016 2066 -5.8239 7.80055e-05 -2.38256 0.00114378 0.000400493 -0.00672078 +EDGE3 2015 2066 -6.21408 4.37576 -2.4204 0.00113157 0.00491068 0.126303 +EDGE3 2016 2065 -5.97451 -4.38431 -2.32349 0.0028395 0.000518966 -0.126846 +EDGE3 2017 2067 -5.80374 0.00506115 -2.38624 0.00253928 -0.00218819 0.00485385 +EDGE3 2016 2067 -6.2197 4.37089 -2.42721 -0.0024466 0.00569053 0.134454 +EDGE3 2017 2066 -5.97597 -4.39096 -2.33083 0.0049088 0.0070123 -0.127994 +EDGE3 2018 2068 -5.82648 -0.00861741 -2.37066 0.00697215 0.000547904 -0.00279348 +EDGE3 2017 2068 -6.19444 4.35555 -2.42256 0.000219624 -0.0110437 0.123259 +EDGE3 2018 2067 -5.97059 -4.38785 -2.31398 1.04194e-05 0.00621861 -0.12852 +EDGE3 2019 2069 -5.80385 -0.00352564 -2.36774 -0.00704168 0.000723321 -0.00191423 +EDGE3 2018 2069 -6.21276 4.32614 -2.40585 -0.00160973 0.00251451 0.130108 +EDGE3 2019 2068 -5.9617 -4.34041 -2.31218 -0.00708811 -0.00108708 -0.125522 +EDGE3 2020 2070 -5.83385 0.00635566 -2.3591 0.000765425 -0.00515953 -0.00173899 +EDGE3 2019 2070 -6.20354 4.30528 -2.38995 0.00356041 0.00194851 0.125916 +EDGE3 2020 2069 -5.99653 -4.32351 -2.31091 0.00615782 0.00345513 -0.12581 +EDGE3 2021 2071 -5.83393 0.0100619 -2.34017 0.000727191 0.00295602 0.00110959 +EDGE3 2020 2071 -6.20915 4.30663 -2.38045 0.0100873 -0.00218948 0.124519 +EDGE3 2021 2070 -5.97817 -4.32804 -2.29347 -0.0105248 0.00268003 -0.122087 +EDGE3 2022 2072 -5.83059 0.00238502 -2.32805 0.00647476 0.00336423 0.000347121 +EDGE3 2021 2072 -6.21032 4.26182 -2.36848 0.000354677 -0.00429968 0.129391 +EDGE3 2022 2071 -5.98414 -4.30602 -2.27938 -0.00124225 -0.0037437 -0.123231 +EDGE3 2023 2073 -5.83805 -0.0115723 -2.33592 -0.00125895 0.00622693 0.00276862 +EDGE3 2022 2073 -6.21702 4.27521 -2.38644 -0.00671104 -0.00493245 0.130302 +EDGE3 2023 2072 -5.9682 -4.28582 -2.29304 0.000612942 0.000517881 -0.122715 +EDGE3 2024 2074 -5.83251 0.00559975 -2.33102 -0.0104946 0.0164411 0.00527033 +EDGE3 2023 2074 -6.24346 4.25569 -2.35235 -0.0127289 -0.00158394 0.122382 +EDGE3 2024 2073 -5.98361 -4.27659 -2.27014 0.000852951 -0.000268478 -0.124245 +EDGE3 2025 2075 -5.84432 -0.0043367 -2.30416 0.00142142 -0.0139681 0.0054916 +EDGE3 2024 2075 -6.21793 4.23589 -2.38595 -0.00411979 0.00232766 0.130071 +EDGE3 2025 2074 -5.97864 -4.27134 -2.27045 0.000218453 0.00108944 -0.12459 +EDGE3 2026 2076 -5.84998 -0.00841108 -2.30584 -0.00659239 -0.0041332 0.0008237 +EDGE3 2025 2076 -6.23664 4.24875 -2.35552 -0.000885832 -0.00414104 0.122379 +EDGE3 2026 2075 -5.97911 -4.23375 -2.27409 0.00146301 0.00393549 -0.126333 +EDGE3 2027 2077 -5.85399 -0.00585114 -2.28287 -0.00519583 0.00325914 -0.00544765 +EDGE3 2026 2077 -6.22213 4.22228 -2.35188 0.00435178 -0.0022694 0.124392 +EDGE3 2027 2076 -5.98967 -4.25109 -2.24203 -0.00117375 -0.000104374 -0.124877 +EDGE3 2028 2078 -5.8556 -0.0145199 -2.28983 -0.00370232 0.000997988 0.00241736 +EDGE3 2027 2078 -6.23325 4.20675 -2.32378 -0.00389323 -0.00590218 0.132073 +EDGE3 2028 2077 -5.99815 -4.21702 -2.2503 0.00131463 0.00908124 -0.127731 +EDGE3 2029 2079 -5.86068 -0.000478759 -2.28712 -0.00291423 0.00643992 0.00393346 +EDGE3 2028 2079 -6.22131 4.1642 -2.33212 0.00327394 -0.00161573 0.120087 +EDGE3 2029 2078 -5.99865 -4.18534 -2.25262 -0.00351711 -0.00678459 -0.129411 +EDGE3 2030 2080 -5.85913 0.00446869 -2.28147 0.000442265 0.00113292 -0.00210327 +EDGE3 2029 2080 -6.24286 4.17357 -2.31826 0.00177325 0.00623765 0.134839 +EDGE3 2030 2079 -5.99571 -4.17766 -2.24153 0.00919467 0.00274864 -0.128124 +EDGE3 2031 2081 -5.85781 -0.0160372 -2.27548 -0.00382007 -0.00619762 0.000436276 +EDGE3 2030 2081 -6.22337 4.14928 -2.30504 0.000240443 -0.00183813 0.125692 +EDGE3 2031 2080 -6.01474 -4.16035 -2.22424 0.0023934 0.00116799 -0.130487 +EDGE3 2032 2082 -5.84634 -0.0062411 -2.25471 0.00865758 -0.00232937 -0.00418461 +EDGE3 2031 2082 -6.22871 4.13936 -2.30863 -0.00277793 -0.00107957 0.132704 +EDGE3 2032 2081 -6.00274 -4.16545 -2.21108 0.000359335 -0.00290276 -0.118996 +EDGE3 2033 2083 -5.85054 0.00949504 -2.24279 -0.00635169 0.00243061 -0.00338636 +EDGE3 2032 2083 -6.23964 4.12851 -2.28834 -0.00215614 0.00680466 0.115213 +EDGE3 2033 2082 -6.00463 -4.14174 -2.22231 -0.00581243 0.00401506 -0.132008 +EDGE3 2034 2084 -5.87131 0.00838508 -2.24898 -0.00244151 -0.00607362 -0.00497452 +EDGE3 2033 2084 -6.24794 4.12703 -2.29615 -0.00197469 0.00280664 0.127452 +EDGE3 2034 2083 -6.02421 -4.12386 -2.19896 0.00349072 0.00482069 -0.127935 +EDGE3 2035 2085 -5.86511 -0.00753024 -2.23834 -0.000541617 0.00813806 -0.0022203 +EDGE3 2034 2085 -6.25948 4.0999 -2.27972 0.00391953 -0.00315987 0.1222 +EDGE3 2035 2084 -6.01528 -4.12841 -2.18704 0.00806919 -0.0040663 -0.128841 +EDGE3 2036 2086 -5.87231 -0.000927928 -2.23761 -0.00699801 0.001145 -0.00780654 +EDGE3 2035 2086 -6.22068 4.09428 -2.26396 0.000181202 -0.00136591 0.130219 +EDGE3 2036 2085 -6.01062 -4.08862 -2.18894 0.00327048 0.00376078 -0.125059 +EDGE3 2037 2087 -5.8695 -0.00294309 -2.23628 -0.00122512 -0.00687364 0.00207906 +EDGE3 2036 2087 -6.24167 4.08063 -2.26722 0.00307176 0.0012598 0.128077 +EDGE3 2037 2086 -6.01905 -4.08751 -2.16404 -0.0127306 -0.000965616 -0.13013 +EDGE3 2038 2088 -5.87968 -0.00743799 -2.23356 -0.00187816 0.00561564 -0.00257699 +EDGE3 2037 2088 -6.26274 4.04235 -2.27455 -0.00104656 -0.00614102 0.129228 +EDGE3 2038 2087 -6.01639 -4.06037 -2.18795 -0.00952976 0.00116822 -0.122361 +EDGE3 2039 2089 -5.86936 0.0040752 -2.20638 0.000257152 0.00160038 0.000578811 +EDGE3 2038 2089 -6.2602 4.03527 -2.25464 -0.00531985 0.00681172 0.117852 +EDGE3 2039 2088 -6.00039 -4.04052 -2.16153 -0.0042891 -0.000712407 -0.13484 +EDGE3 2040 2090 -5.87311 0.00831174 -2.20651 -0.00266108 -0.0116939 -0.00732333 +EDGE3 2039 2090 -6.25099 4.01829 -2.25358 -0.000399423 0.00143383 0.116277 +EDGE3 2040 2089 -6.04156 -4.03864 -2.15024 0.00151055 -0.000227002 -0.134871 +EDGE3 2041 2091 -5.88369 0.00800965 -2.20798 0.00321538 0.00583027 0.0021009 +EDGE3 2040 2091 -6.26768 3.99771 -2.24542 -0.00529336 -0.00064505 0.125849 +EDGE3 2041 2090 -6.0111 -4.01032 -2.15688 -0.0051762 0.00233999 -0.127105 +EDGE3 2042 2092 -5.89063 0.000370012 -2.19317 -0.00209198 0.00170177 0.00051837 +EDGE3 2041 2092 -6.24767 3.99418 -2.23575 0.0068385 0.00698524 0.118561 +EDGE3 2042 2091 -6.02067 -4.01682 -2.17581 -0.000193594 -0.00142719 -0.133227 +EDGE3 2043 2093 -5.89392 -8.55446e-05 -2.19132 -0.00353716 -9.00468e-05 -0.00858542 +EDGE3 2042 2093 -6.25764 3.95972 -2.23607 0.00451716 0.00473665 0.122068 +EDGE3 2043 2092 -6.0342 -3.99828 -2.14328 0.00666641 -0.0047847 -0.114355 +EDGE3 2044 2094 -5.89738 0.00615196 -2.16601 0.00463567 0.000952493 0.000717161 +EDGE3 2043 2094 -6.26914 3.96955 -2.21102 0.0100643 0.00323086 0.113249 +EDGE3 2044 2093 -6.01532 -3.9753 -2.12826 -0.00666583 0.000778069 -0.126675 +EDGE3 2045 2095 -5.9074 -0.00391655 -2.17908 0.00334858 0.00458424 -0.00117983 +EDGE3 2044 2095 -6.24863 3.93941 -2.20677 -0.000369341 -0.0029873 0.119971 +EDGE3 2045 2094 -6.03339 -3.97444 -2.12564 0.00202228 0.00965025 -0.127493 +EDGE3 2046 2096 -5.89056 0.00343853 -2.16229 0.00014085 -0.0031088 -0.00446368 +EDGE3 2045 2096 -6.25946 3.93629 -2.21792 -0.00840579 0.00637255 0.110481 +EDGE3 2046 2095 -6.03598 -3.94212 -2.11982 0.0034826 -0.00953041 -0.117463 +EDGE3 2047 2097 -5.90413 -0.00970724 -2.13146 0.000712657 -0.00221239 -0.00229294 +EDGE3 2046 2097 -6.26189 3.92256 -2.19438 0.00479461 -0.00113208 0.122579 +EDGE3 2047 2096 -6.02093 -3.92911 -2.10968 -0.0124571 0.000737624 -0.132679 +EDGE3 2048 2098 -5.9095 0.00881503 -2.14741 -0.00537507 -0.00561318 0.00606886 +EDGE3 2047 2098 -6.25978 3.90568 -2.19037 -0.00672361 0.00161057 0.129421 +EDGE3 2048 2097 -6.02379 -3.92629 -2.1073 -0.000847256 0.000310481 -0.125608 +EDGE3 2049 2099 -5.92216 -0.00660758 -2.1383 -0.0047532 -0.00565192 0.00346489 +EDGE3 2048 2099 -6.2708 3.87426 -2.18496 0.00179536 0.00121711 0.114605 +EDGE3 2049 2098 -6.0221 -3.90099 -2.09934 0.00383356 -0.00277464 -0.124785 +EDGE3 2050 2100 -5.92667 0.00175771 -2.12584 0.00108367 -0.00313783 0.000666733 +EDGE3 2049 2100 -6.27179 3.88072 -2.1908 0.0024905 0.00965048 0.123347 +EDGE3 2050 2099 -6.02507 -3.89527 -2.08976 -0.00481411 0.00495421 -0.127296 +EDGE3 2051 2101 -5.93393 0.00979347 -2.12608 0.00396038 0.000821505 0.0019976 +EDGE3 2050 2101 -6.26942 3.86654 -2.16611 -0.00395801 -0.00287421 0.129068 +EDGE3 2051 2100 -6.03857 -3.86839 -2.07855 0.000358259 0.00107249 -0.124883 +EDGE3 2052 2102 -5.90758 0.00308433 -2.12404 -0.0033241 0.00645193 -0.0012438 +EDGE3 2051 2102 -6.27038 3.85507 -2.16632 -0.00116234 0.00212495 0.123367 +EDGE3 2052 2101 -6.05148 -3.87227 -2.06772 0.00202365 -0.00908501 -0.123291 +EDGE3 2053 2103 -5.91533 -0.00751206 -2.09308 0.00349201 0.00481191 0.00400347 +EDGE3 2052 2103 -6.26918 3.84046 -2.14182 0.000346807 0.00338979 0.129896 +EDGE3 2054 2104 -5.93149 0.00908506 -2.09416 -0.00273292 -0.00148151 -0.00370212 +EDGE3 2053 2102 -6.04058 -3.84883 -2.06405 0.0064755 0.00402051 -0.131411 +EDGE3 2053 2104 -6.29198 3.82114 -2.14431 -0.0053049 -0.00671709 0.125853 +EDGE3 2054 2103 -6.04273 -3.82665 -2.05713 -0.00168238 -0.000167931 -0.137384 +EDGE3 2055 2105 -5.91969 -0.00430229 -2.07836 -0.00713583 0.00467845 -0.0039021 +EDGE3 2054 2105 -6.28623 3.8111 -2.14904 -0.00768072 -0.001408 0.128283 +EDGE3 2056 2106 -5.93314 -0.000461604 -2.08572 -0.00594782 0.00270033 -0.00448599 +EDGE3 2055 2104 -6.05003 -3.80292 -2.04927 -0.011553 -0.000521331 -0.128087 +EDGE3 2055 2106 -6.27874 3.79357 -2.11565 -0.00119753 0.00605238 0.13569 +EDGE3 2056 2105 -6.03948 -3.81879 -2.04731 -0.00206279 0.000526761 -0.127595 +EDGE3 2057 2107 -5.93791 0.00623255 -2.08121 -0.0022489 -0.00395187 0.00768184 +EDGE3 2056 2107 -6.26979 3.75976 -2.11732 -0.00247653 -0.00188549 0.129675 +EDGE3 2057 2106 -6.07606 -3.77956 -2.03081 0.00149475 0.0042671 -0.124208 +EDGE3 2058 2108 -5.92822 0.0088042 -2.05192 0.00381683 0.000620686 -0.00965019 +EDGE3 2057 2108 -6.29437 3.76767 -2.11551 0.00109404 -0.0113543 0.128986 +EDGE3 2058 2107 -6.03879 -3.78978 -2.04012 0.00751838 0.00694709 -0.124118 +EDGE3 2059 2109 -5.93245 -0.0113038 -2.05206 -0.00369534 -0.00320599 -0.00649021 +EDGE3 2058 2109 -6.2967 3.70899 -2.11219 0.00107844 0.0026395 0.1366 +EDGE3 2059 2108 -6.05884 -3.76036 -2.0264 0.00622424 0.00225682 -0.12689 +EDGE3 2060 2110 -5.9355 -0.0190349 -2.07067 0.00290023 0.000620301 0.00730811 +EDGE3 2059 2110 -6.28739 3.72561 -2.07671 -0.00223055 -0.000211957 0.123687 +EDGE3 2061 2111 -5.92652 0.00189824 -2.04278 -0.00711868 0.00821108 -0.00122415 +EDGE3 2060 2109 -6.04357 -3.72466 -2.00346 0.00692385 -0.00728787 -0.126196 +EDGE3 2060 2111 -6.27882 3.70464 -2.08489 0.00548529 -0.00206663 0.130796 +EDGE3 2061 2110 -6.0465 -3.7205 -2.00394 0.000299136 0.0120955 -0.123387 +EDGE3 2062 2112 -5.95038 -0.0226301 -2.03134 0.000446199 0.00143466 -0.00327498 +EDGE3 2061 2112 -6.29146 3.68536 -2.10226 -0.00661116 -0.000432953 0.117982 +EDGE3 2062 2111 -6.0493 -3.72286 -1.99942 0.00435613 0.00179494 -0.126614 +EDGE3 2063 2113 -5.93952 0.000585731 -2.02381 -0.00118808 -0.000536908 -0.00812612 +EDGE3 2062 2113 -6.29619 3.67743 -2.07443 -0.00225026 -0.00392104 0.126678 +EDGE3 2063 2112 -6.08045 -3.71915 -1.9964 0.0024397 -0.00454503 -0.130236 +EDGE3 2064 2114 -5.94825 -0.000532564 -2.01971 -0.00369132 0.00909343 0.00216733 +EDGE3 2063 2114 -6.29575 3.68247 -2.06419 0.00953423 -0.00405272 0.119145 +EDGE3 2064 2113 -6.06373 -3.68082 -1.97632 -0.00544145 0.00372757 -0.125031 +EDGE3 2065 2115 -5.95068 0.00513786 -2.01439 0.00143478 0.00478867 0.00409069 +EDGE3 2064 2115 -6.29672 3.6439 -2.05649 0.000561371 0.00142515 0.126307 +EDGE3 2065 2114 -6.05683 -3.66435 -1.96301 -0.0067498 -0.000446725 -0.114579 +EDGE3 2066 2116 -5.95544 0.00671604 -2.021 -0.00103876 5.14945e-06 -0.00130655 +EDGE3 2065 2116 -6.28359 3.65731 -2.07078 0.005645 0.00563761 0.129405 +EDGE3 2066 2115 -6.05639 -3.6417 -1.97955 0.000542635 0.000584542 -0.128521 +EDGE3 2067 2117 -5.94927 -0.0140771 -2.01216 0.00683763 0.00606834 0.00272283 +EDGE3 2066 2117 -6.31134 3.60498 -2.04821 0.00153988 -0.00475633 0.120193 +EDGE3 2067 2116 -6.06027 -3.6338 -1.97689 -0.00555853 0.00160332 -0.120354 +EDGE3 2068 2118 -5.953 -0.00371038 -1.99547 -0.00271618 0.00776533 0.00241446 +EDGE3 2067 2118 -6.30762 3.61152 -2.03263 0.0032646 -0.00301803 0.126952 +EDGE3 2068 2117 -6.06969 -3.61773 -1.95472 -0.00850289 0.00116892 -0.125973 +EDGE3 2068 2119 -6.29498 3.57367 -2.03019 -0.00540186 -0.00346286 0.134715 +EDGE3 2069 2119 -5.98185 0.0114605 -1.9936 0.00290407 0.00276769 0.00239547 +EDGE3 2070 2120 -5.97477 -0.00316827 -1.96173 0.00186382 0.00515816 -0.00656733 +EDGE3 2069 2118 -6.0582 -3.58813 -1.9671 0.003653 -0.00412479 -0.120012 +EDGE3 2069 2120 -6.31353 3.56648 -2.02285 0.00834139 0.00168444 0.127785 +EDGE3 2070 2119 -6.06804 -3.58682 -1.93565 -0.00269927 0.0014436 -0.124743 +EDGE3 2071 2121 -5.98216 -0.00571616 -1.96118 0.00317048 -0.00589334 -0.000540103 +EDGE3 2070 2121 -6.33194 3.54488 -2.00153 0.0136365 -0.00761714 0.119832 +EDGE3 2071 2120 -6.07413 -3.56923 -1.91845 -0.00345911 -0.00121302 -0.123701 +EDGE3 2071 2122 -6.29725 3.53959 -2.00067 -0.00314443 0.000628238 0.128557 +EDGE3 2072 2122 -5.96748 -0.0015084 -1.99386 -0.00951151 0.000348671 0.00744 +EDGE3 2073 2123 -5.97319 0.011017 -1.96971 -0.00910832 0.00358224 -0.00199302 +EDGE3 2072 2121 -6.0773 -3.55398 -1.92424 0.00153828 -0.00143892 -0.13044 +EDGE3 2072 2123 -6.31332 3.5188 -1.99706 0.00404255 0.000858063 0.124509 +EDGE3 2073 2122 -6.06986 -3.53597 -1.94962 -0.00103369 0.0028723 -0.126331 +EDGE3 2074 2124 -5.98892 -0.000392381 -1.95866 -0.000804872 0.00684446 -0.000457259 +EDGE3 2073 2124 -6.28515 3.52381 -2.00725 0.00276886 0.00825662 0.117109 +EDGE3 2074 2123 -6.07522 -3.52987 -1.89962 0.000737912 -0.000937212 -0.116506 +EDGE3 2075 2125 -5.96068 0.0173979 -1.9445 0.00103332 0.00293935 0.00287142 +EDGE3 2074 2125 -6.32713 3.50678 -1.9772 0.00174963 0.00332514 0.120492 +EDGE3 2076 2126 -5.97277 -0.0178712 -1.9284 -0.000101728 -0.00608443 0.00703662 +EDGE3 2075 2124 -6.06783 -3.53235 -1.90033 -0.00589156 0.0042456 -0.126481 +EDGE3 2075 2126 -6.31638 3.47845 -1.96574 -0.00313076 -0.00266076 0.117886 +EDGE3 2076 2125 -6.08533 -3.48031 -1.91061 0.000601945 -0.00100547 -0.1291 +EDGE3 2077 2127 -5.98331 -0.00234423 -1.93982 0.00365559 0.00331466 0.0024518 +EDGE3 2076 2127 -6.32156 3.46942 -1.96339 -0.000680103 -0.0101067 0.120489 +EDGE3 2077 2126 -6.07254 -3.47158 -1.90369 0.0114106 0.000478325 -0.133952 +EDGE3 2078 2128 -5.98693 -0.00280221 -1.91354 0.00215617 0.000803247 -0.000263122 +EDGE3 2077 2128 -6.31929 3.4433 -1.96018 0.00296542 0.000386859 0.119064 +EDGE3 2078 2127 -6.08694 -3.4604 -1.88881 -0.0024729 -0.00829517 -0.130498 +EDGE3 2079 2129 -5.98147 0.0070781 -1.91989 -0.00159125 -0.000797719 -0.00341666 +EDGE3 2078 2129 -6.30045 3.44762 -1.96472 -0.00144504 0.00174931 0.117837 +EDGE3 2079 2128 -6.08249 -3.45943 -1.87459 -0.00387627 -0.000661715 -0.124688 +EDGE3 2080 2130 -5.97924 -0.000312655 -1.91332 -0.0105905 -0.00193327 0.000221905 +EDGE3 2079 2130 -6.33803 3.42882 -1.94711 -0.00341034 0.00823967 0.11694 +EDGE3 2081 2131 -5.98859 0.00279185 -1.89873 -0.00160391 -0.00207205 -0.00417025 +EDGE3 2080 2129 -6.08952 -3.44871 -1.86505 -0.00164381 0.00248843 -0.126939 +EDGE3 2080 2131 -6.33061 3.40838 -1.94915 0.00291881 0.00797559 0.132987 +EDGE3 2081 2130 -6.0788 -3.41594 -1.87535 -0.0013287 -0.00791277 -0.125402 +EDGE3 2082 2132 -6.0015 -0.00652335 -1.89215 -4.18205e-05 0.00102996 0.00807322 +EDGE3 2081 2132 -6.32091 3.39962 -1.91889 -0.00143505 0.00151983 0.123785 +EDGE3 2082 2131 -6.08934 -3.39579 -1.85926 -0.0111783 0.00252409 -0.117537 +EDGE3 2083 2133 -5.98507 -0.0120733 -1.86438 0.0088407 -0.000948591 0.00930804 +EDGE3 2082 2133 -6.33084 3.40599 -1.92476 -2.61182e-05 -0.00179654 0.126582 +EDGE3 2083 2132 -6.0878 -3.40112 -1.84172 -0.000539774 0.000508492 -0.115756 +EDGE3 2084 2134 -6.01648 0.00418231 -1.88188 0.000283529 0.00925755 0.00191758 +EDGE3 2083 2134 -6.32832 3.34385 -1.93447 0.0100678 9.59947e-05 0.127495 +EDGE3 2084 2133 -6.09274 -3.36285 -1.83756 0.0015268 -0.00190316 -0.121878 +EDGE3 2085 2135 -6.00625 0.0115873 -1.86914 -0.00734993 -0.00171104 -0.00343614 +EDGE3 2084 2135 -6.34637 3.36636 -1.90868 0.00178518 -0.00195286 0.124479 +EDGE3 2085 2134 -6.07863 -3.35867 -1.84407 -0.0073883 -1.90668e-05 -0.126297 +EDGE3 2086 2136 -6.00136 0.00962977 -1.86404 0.00681084 -0.00439823 -0.000295294 +EDGE3 2085 2136 -6.31204 3.33194 -1.8932 0.00303882 0.0115107 0.125339 +EDGE3 2086 2135 -6.0749 -3.37437 -1.82204 0.00312573 0.00548964 -0.129293 +EDGE3 2087 2137 -6.00067 -0.00189323 -1.8569 0.00658947 0.00517575 -0.00109841 +EDGE3 2086 2137 -6.34788 3.30463 -1.88166 -0.00365125 0.00527173 0.122573 +EDGE3 2087 2136 -6.08537 -3.31952 -1.84878 -0.00232596 -0.00728576 -0.121916 +EDGE3 2088 2138 -5.9965 -0.00206411 -1.84616 -0.00791901 0.00103662 -0.00379793 +EDGE3 2087 2138 -6.33761 3.29809 -1.8893 -0.00339555 0.00220343 0.126114 +EDGE3 2088 2137 -6.09966 -3.30036 -1.80643 0.00715213 -0.00281162 -0.134379 +EDGE3 2089 2139 -5.99174 -0.0132134 -1.82407 -0.00141107 -0.00367747 0.00326636 +EDGE3 2088 2139 -6.33806 3.27951 -1.87007 0.00226315 0.0142096 0.116329 +EDGE3 2089 2138 -6.08719 -3.30371 -1.82199 -0.010199 -0.00269967 -0.122222 +EDGE3 2090 2140 -6.00763 0.0110368 -1.84088 -0.00368553 0.0044039 0.00242902 +EDGE3 2089 2140 -6.33415 3.27942 -1.87885 -0.00402238 0.00323564 0.120321 +EDGE3 2090 2139 -6.08789 -3.27756 -1.80309 0.00483719 -0.00178446 -0.123195 +EDGE3 2091 2141 -6.00517 -0.00312004 -1.82225 0.00150712 0.0016927 0.00909287 +EDGE3 2090 2141 -6.34152 3.24619 -1.87426 -6.66586e-05 -0.00323963 0.123026 +EDGE3 2091 2140 -6.08532 -3.27743 -1.78561 0.00225822 -0.00210238 -0.122902 +EDGE3 2092 2142 -6.03401 0.00626047 -1.82865 0.00698572 0.00196595 0.00153133 +EDGE3 2091 2142 -6.33349 3.24546 -1.86974 -0.00453172 0.00936996 0.132012 +EDGE3 2092 2141 -6.1117 -3.26464 -1.7908 -0.00115097 0.00475354 -0.127528 +EDGE3 2093 2143 -6.00735 0.0142423 -1.82259 -0.00461933 -0.00242872 0.00164205 +EDGE3 2092 2143 -6.31528 3.21693 -1.84663 0.00271098 -0.0110172 0.123544 +EDGE3 2093 2142 -6.08444 -3.22965 -1.77742 0.00457179 0.00343976 -0.120475 +EDGE3 2094 2144 -6.01503 -0.0258424 -1.79562 0.00153992 0.00118445 -0.0107001 +EDGE3 2093 2144 -6.33681 3.21361 -1.832 -0.00727946 0.00135847 0.125971 +EDGE3 2094 2143 -6.11136 -3.23391 -1.77058 -0.000747774 0.00142893 -0.13029 +EDGE3 2095 2145 -6.00283 0.00428907 -1.79587 0.000318612 -0.00216324 -0.000631388 +EDGE3 2094 2145 -6.35785 3.18705 -1.82212 0.000896689 -0.0153748 0.124053 +EDGE3 2095 2144 -6.07596 -3.2214 -1.75577 0.00790089 0.0031951 -0.126049 +EDGE3 2096 2146 -6.02561 0.0080687 -1.79064 -0.00507079 0.00328523 0.00183576 +EDGE3 2095 2146 -6.337 3.17915 -1.82029 -0.00493707 0.0112835 0.129667 +EDGE3 2096 2145 -6.08761 -3.19806 -1.75927 -0.00446779 -0.001626 -0.123207 +EDGE3 2097 2147 -6.01608 -0.00307987 -1.78843 -0.00292477 0.00055812 -0.00100634 +EDGE3 2096 2147 -6.34148 3.17192 -1.81007 -0.00231259 -0.0127814 0.126525 +EDGE3 2097 2146 -6.1011 -3.18861 -1.73935 -5.00321e-05 -0.00405163 -0.120742 +EDGE3 2098 2148 -6.02953 0.0192381 -1.76784 0.00358078 0.0164029 0.00620056 +EDGE3 2097 2148 -6.34781 3.14471 -1.8083 0.00189213 -0.00610294 0.127296 +EDGE3 2098 2147 -6.12284 -3.15342 -1.71728 0.00217708 0.00334693 -0.128702 +EDGE3 2099 2149 -6.027 0.0149826 -1.7701 -0.00181979 0.00372934 0.00120963 +EDGE3 2098 2149 -6.34578 3.16253 -1.78907 -0.0108032 0.00262441 0.123235 +EDGE3 2099 2148 -6.10303 -3.1315 -1.72147 0.000696869 -0.00218441 -0.130784 +EDGE3 2100 2150 -6.02553 0.00773579 -1.73273 -0.0102786 0.0104801 -0.00180978 +EDGE3 2099 2150 -6.3549 3.12636 -1.78701 0.0145635 0.00922558 0.122406 +EDGE3 2100 2149 -6.08038 -3.13274 -1.71283 0.00250838 -0.00395404 -0.1218 +EDGE3 2101 2151 -6.03733 -0.0317082 -1.77018 -0.00136621 -0.00191629 0.00706098 +EDGE3 2100 2151 -6.33985 3.08642 -1.76906 -0.00482753 -0.00366189 0.132566 +EDGE3 2101 2150 -6.1141 -3.10638 -1.72232 -0.00832088 0.00416842 -0.122835 +EDGE3 2102 2152 -6.03043 0.00073681 -1.72199 -0.00695688 0.00389192 0.0114215 +EDGE3 2101 2152 -6.34919 3.08712 -1.75736 -0.000196628 -0.00857404 0.122979 +EDGE3 2102 2151 -6.0997 -3.09302 -1.71509 -0.00054366 -0.0039425 -0.123984 +EDGE3 2103 2153 -6.03353 0.00575997 -1.72863 -0.000793797 -0.00226973 -0.00308441 +EDGE3 2102 2153 -6.35863 3.0853 -1.7594 0.00169966 0.00122449 0.119839 +EDGE3 2103 2152 -6.11868 -3.08371 -1.70151 -0.00565734 0.00863588 -0.129928 +EDGE3 2104 2154 -6.03913 -0.00903318 -1.72153 0.000441206 -0.0107704 0.00665143 +EDGE3 2103 2154 -6.3513 3.05071 -1.74727 1.85428e-05 0.00455478 0.115662 +EDGE3 2104 2153 -6.11176 -3.06929 -1.7098 -0.00608003 -0.00810215 -0.127324 +EDGE3 2105 2155 -6.02528 -0.00434033 -1.72147 -0.00392665 0.00117417 -0.0025338 +EDGE3 2104 2155 -6.36168 3.04685 -1.76197 -0.00883081 0.00551195 0.125251 +EDGE3 2105 2154 -6.11603 -3.04845 -1.67309 -0.00779575 -0.000829919 -0.130793 +EDGE3 2106 2156 -6.0549 0.0118093 -1.70126 0.00352563 0.000499884 -6.95599e-05 +EDGE3 2105 2156 -6.36003 3.02673 -1.75821 0.00425138 -0.00225235 0.129514 +EDGE3 2106 2155 -6.12348 -3.04461 -1.6753 -0.00312301 0.00134217 -0.124023 +EDGE3 2107 2157 -6.06793 0.0120463 -1.69289 0.000101849 0.00220657 -0.00448867 +EDGE3 2106 2157 -6.35827 3.00143 -1.75305 -0.000481849 0.00468383 0.122905 +EDGE3 2107 2156 -6.13058 -3.02213 -1.67988 0.00626093 0.000690364 -0.133951 +EDGE3 2108 2158 -6.04005 -0.0119155 -1.69567 -0.00236322 -0.0035188 -0.00341967 +EDGE3 2107 2158 -6.36007 3.00323 -1.72501 0.000254628 -0.00222055 0.13303 +EDGE3 2108 2157 -6.10696 -3.02373 -1.66927 -0.00990192 -0.00440656 -0.126474 +EDGE3 2109 2159 -6.05669 -0.00487156 -1.66083 0.00262555 -0.000106343 0.00409873 +EDGE3 2108 2159 -6.3709 2.9766 -1.7174 -0.00384179 -0.00474646 0.126509 +EDGE3 2109 2158 -6.12488 -2.97947 -1.67041 0.00172027 -0.00221907 -0.127918 +EDGE3 2110 2160 -6.05226 0.00580043 -1.67865 -0.00604458 0.00589595 -0.00127039 +EDGE3 2109 2160 -6.36689 2.97288 -1.71598 -0.00314415 -0.00235884 0.119416 +EDGE3 2110 2159 -6.11442 -2.97335 -1.64219 0.00202833 0.00581036 -0.1219 +EDGE3 2111 2161 -6.04573 -0.0119217 -1.68149 -0.0113585 -0.00672606 -0.00117277 +EDGE3 2110 2161 -6.36804 2.94244 -1.70661 -0.00107658 0.00394848 0.123894 +EDGE3 2111 2160 -6.12621 -2.96081 -1.63363 -0.00916809 0.000980626 -0.120193 +EDGE3 2112 2162 -6.05338 -0.000203396 -1.65019 -0.00904445 0.00661086 -0.00284396 +EDGE3 2111 2162 -6.35452 2.9241 -1.70362 -0.0022817 -0.0022037 0.1257 +EDGE3 2112 2161 -6.13453 -2.93853 -1.62646 -0.000721912 0.00441845 -0.118948 +EDGE3 2113 2163 -6.05195 0.0015401 -1.65438 0.00462622 -0.00560956 -0.00125981 +EDGE3 2112 2163 -6.362 2.91011 -1.6789 -0.00427048 -0.00475044 0.136729 +EDGE3 2113 2162 -6.13157 -2.92505 -1.63907 0.00054087 0.00506513 -0.126685 +EDGE3 2114 2164 -6.05391 -0.0110752 -1.64791 -0.00183539 0.00680735 0.00778786 +EDGE3 2113 2164 -6.37927 2.9022 -1.68537 -0.00155023 -0.000636592 0.127315 +EDGE3 2114 2163 -6.13008 -2.91453 -1.61082 -0.00131687 0.00164425 -0.115962 +EDGE3 2115 2165 -6.05837 -0.00536234 -1.64635 0.00531262 0.00272633 0.00390719 +EDGE3 2114 2165 -6.36506 2.89054 -1.67492 0.00788926 0.000512568 0.127069 +EDGE3 2115 2164 -6.13556 -2.88816 -1.61398 -0.00353546 -0.00426429 -0.122942 +EDGE3 2116 2166 -6.05586 0.0164184 -1.63172 -0.00456012 0.00524413 -0.00572001 +EDGE3 2115 2166 -6.37999 2.87212 -1.65844 0.00647418 -0.00297022 0.131947 +EDGE3 2116 2165 -6.12219 -2.8845 -1.60356 -0.00487163 -0.00215806 -0.132524 +EDGE3 2117 2167 -6.0765 -0.00431003 -1.61947 0.00140154 0.00572974 0.00180628 +EDGE3 2116 2167 -6.37091 2.84255 -1.65185 -0.0130899 0.00296803 0.131669 +EDGE3 2117 2166 -6.11041 -2.8769 -1.59221 -0.00178785 0.00305872 -0.12958 +EDGE3 2118 2168 -6.07319 -0.00338633 -1.60982 0.000314876 -0.0152391 0.00097525 +EDGE3 2117 2168 -6.3836 2.84333 -1.64003 0.00150838 -0.00290157 0.123579 +EDGE3 2118 2167 -6.13013 -2.861 -1.57997 0.00508284 0.00137805 -0.132691 +EDGE3 2119 2169 -6.06416 -0.000941054 -1.60049 0.00652932 -0.00301904 -0.00397358 +EDGE3 2118 2169 -6.37021 2.83421 -1.63404 0.00254658 -0.00852544 0.132168 +EDGE3 2119 2168 -6.12462 -2.8317 -1.56718 0.00200924 -0.00249719 -0.12779 +EDGE3 2120 2170 -6.07631 0.00591338 -1.60152 -0.0042621 -0.00776457 0.00956044 +EDGE3 2119 2170 -6.39578 2.82416 -1.65718 -0.00514111 0.00302487 0.126869 +EDGE3 2120 2169 -6.1271 -2.81399 -1.57315 -0.00133484 -0.00169273 -0.123637 +EDGE3 2121 2171 -6.07852 0.000810951 -1.58402 0.00596351 -0.00547316 0.0101805 +EDGE3 2120 2171 -6.36135 2.80402 -1.63166 -0.00455756 0.0038687 0.12453 +EDGE3 2121 2170 -6.13231 -2.80301 -1.55883 0.00472195 0.0070168 -0.121146 +EDGE3 2122 2172 -6.07008 -0.0017845 -1.60475 0.00259908 0.000368062 0.0018074 +EDGE3 2121 2172 -6.38381 2.77421 -1.62897 0.000865094 0.00416186 0.136695 +EDGE3 2122 2171 -6.14235 -2.78041 -1.55596 0.00346219 0.00324749 -0.120924 +EDGE3 2123 2173 -6.07456 0.00110896 -1.57546 0.004553 0.00214091 -0.00303332 +EDGE3 2122 2173 -6.37167 2.7682 -1.6128 -0.000399282 -0.00363955 0.130541 +EDGE3 2123 2172 -6.13029 -2.79074 -1.54255 -0.00213953 0.00412228 -0.122702 +EDGE3 2124 2174 -6.07244 0.0203096 -1.57634 0.00338031 -0.00450822 -0.00219025 +EDGE3 2123 2174 -6.37143 2.74232 -1.617 -0.00580911 0.00709085 0.119948 +EDGE3 2124 2173 -6.13209 -2.77122 -1.55071 -0.00214452 0.00303414 -0.124703 +EDGE3 2125 2175 -6.08263 0.00116373 -1.57643 0.0123183 0.00337668 -0.00368489 +EDGE3 2124 2175 -6.37265 2.7365 -1.60193 0.00926088 -0.00486739 0.124118 +EDGE3 2125 2174 -6.12399 -2.76354 -1.53341 0.00403033 -0.00215533 -0.129689 +EDGE3 2126 2176 -6.08205 -0.0048357 -1.54839 -0.00430769 -0.0073771 0.000171346 +EDGE3 2125 2176 -6.37034 2.71354 -1.59441 0.00126459 -0.00375126 0.132072 +EDGE3 2126 2175 -6.14745 -2.74803 -1.52824 -0.000883027 -0.00460627 -0.128433 +EDGE3 2127 2177 -6.10591 0.000609767 -1.53792 -0.000622008 -0.0028017 0.00022089 +EDGE3 2126 2177 -6.38215 2.70491 -1.58228 0.000172778 0.00387577 0.122669 +EDGE3 2127 2176 -6.12158 -2.71872 -1.535 -0.0085379 0.000986664 -0.123754 +EDGE3 2128 2178 -6.09077 -0.0074687 -1.55364 0.00401524 -0.000991005 -0.00202728 +EDGE3 2127 2178 -6.38272 2.67497 -1.55352 0.00625341 0.000722047 0.127526 +EDGE3 2128 2177 -6.15985 -2.69293 -1.5191 0.000295744 -0.000654235 -0.131033 +EDGE3 2129 2179 -6.09723 -0.00578023 -1.54735 -0.000964619 -0.00710696 -0.00175898 +EDGE3 2128 2179 -6.38609 2.67657 -1.57239 -0.000837059 -0.00398319 0.117444 +EDGE3 2129 2178 -6.14394 -2.685 -1.50108 -0.00654075 0.00555596 -0.127701 +EDGE3 2130 2180 -6.09436 -0.00327573 -1.52755 0.00295263 -0.00187795 0.00216958 +EDGE3 2129 2180 -6.37714 2.651 -1.57105 0.00825667 0.0034253 0.125462 +EDGE3 2130 2179 -6.14308 -2.66974 -1.50666 0.00358796 -0.00641402 -0.117388 +EDGE3 2131 2181 -6.09577 -0.00596404 -1.50406 -0.00211756 0.00412137 -0.00393596 +EDGE3 2130 2181 -6.37517 2.63331 -1.54984 0.000552114 -0.00541878 0.120572 +EDGE3 2131 2180 -6.14972 -2.63524 -1.48873 -0.00326281 -0.00191088 -0.117339 +EDGE3 2132 2182 -6.11207 0.00268296 -1.49052 0.00510036 -0.00257811 -0.00705217 +EDGE3 2131 2182 -6.36456 2.62522 -1.53036 -0.00109818 0.00586741 0.126426 +EDGE3 2132 2181 -6.12752 -2.64179 -1.47741 0.00222706 -0.00516707 -0.12597 +EDGE3 2133 2183 -6.11688 -8.67769e-05 -1.48019 0.00257475 0.00634067 0.000886748 +EDGE3 2132 2183 -6.39302 2.59857 -1.54223 0.000957418 -0.00358733 0.126392 +EDGE3 2133 2182 -6.15706 -2.62245 -1.48218 0.00584931 0.00202588 -0.120456 +EDGE3 2134 2184 -6.09973 -0.0178222 -1.50356 -0.00104042 -0.000329482 0.0070011 +EDGE3 2133 2184 -6.38645 2.61291 -1.5038 0.0017519 -0.00653232 0.129353 +EDGE3 2134 2183 -6.13959 -2.61078 -1.46489 -0.00592665 -0.000108386 -0.11698 +EDGE3 2135 2185 -6.10005 -0.0061933 -1.49553 -0.00203202 0.00415748 -0.0019906 +EDGE3 2134 2185 -6.37266 2.57842 -1.52533 -0.00583527 0.00162562 0.131321 +EDGE3 2135 2184 -6.14496 -2.59396 -1.45414 0.00984246 -0.00287154 -0.128299 +EDGE3 2136 2186 -6.09993 0.0107231 -1.48455 -0.00787635 -0.00168988 -2.50032e-05 +EDGE3 2135 2186 -6.37952 2.58117 -1.49995 -0.00290006 -0.00180907 0.126585 +EDGE3 2136 2185 -6.15098 -2.57152 -1.44654 0.00873902 -0.00732699 -0.121588 +EDGE3 2137 2187 -6.10714 0.0117103 -1.47509 0.00482699 0.000655149 0.00090774 +EDGE3 2136 2187 -6.38518 2.55236 -1.48876 -0.00449889 -0.00660463 0.135141 +EDGE3 2137 2186 -6.16191 -2.56178 -1.43126 -0.00430394 0.0046619 -0.122503 +EDGE3 2138 2188 -6.106 0.00308513 -1.4515 0.0018441 -0.00337575 -0.000502985 +EDGE3 2137 2188 -6.40285 2.53676 -1.50177 -0.000308542 0.000709305 0.120844 +EDGE3 2138 2187 -6.13839 -2.54467 -1.43005 -0.0053218 0.00455299 -0.114026 +EDGE3 2139 2189 -6.11215 -0.00473784 -1.47926 0.00679294 -0.00686528 0.00191059 +EDGE3 2138 2189 -6.37667 2.52462 -1.47615 0.00651111 -0.00572575 0.125506 +EDGE3 2139 2188 -6.15772 -2.5293 -1.43358 0.00144712 0.00197916 -0.124438 +EDGE3 2140 2190 -6.11653 0.0132158 -1.43492 -0.000992057 -0.00542207 -0.00349857 +EDGE3 2139 2190 -6.39125 2.48389 -1.4831 -0.000458761 0.00275437 0.129613 +EDGE3 2140 2189 -6.13765 -2.51636 -1.43566 0.00283962 -0.00291675 -0.12503 +EDGE3 2141 2191 -6.13182 -0.000536986 -1.43488 -0.0033865 0.00311662 0.00325182 +EDGE3 2140 2191 -6.39627 2.47308 -1.46308 0.0021683 0.0021346 0.127294 +EDGE3 2142 2192 -6.10187 -0.000164833 -1.41509 -0.00128835 -0.00975593 -0.0143848 +EDGE3 2141 2190 -6.13596 -2.50414 -1.39065 0.0045157 -0.0128132 -0.131329 +EDGE3 2141 2192 -6.39218 2.45169 -1.47588 -0.00472987 0.00119736 0.116863 +EDGE3 2142 2191 -6.1559 -2.4968 -1.40346 0.00414847 -0.00305708 -0.126816 +EDGE3 2143 2193 -6.12946 -0.0037127 -1.41332 0.00638844 0.00933395 -0.00319108 +EDGE3 2142 2193 -6.40405 2.46818 -1.45208 -0.00375872 -0.0069903 0.129572 +EDGE3 2143 2192 -6.15173 -2.4652 -1.4171 0.00115789 0.000694659 -0.11778 +EDGE3 2144 2194 -6.12063 -0.00987962 -1.42416 0.00257147 -0.0060495 0.00181636 +EDGE3 2143 2194 -6.40232 2.43988 -1.45723 0.00092139 0.00862409 0.128122 +EDGE3 2144 2193 -6.14829 -2.45543 -1.38257 0.000375646 -0.0053709 -0.124203 +EDGE3 2144 2195 -6.36838 2.41735 -1.43774 0.00318859 0.00697568 0.126441 +EDGE3 2145 2195 -6.12206 0.0130165 -1.40111 -0.00104551 0.00435546 0.0041184 +EDGE3 2146 2196 -6.12333 0.00923855 -1.40085 0.000617235 -0.00852599 0.00702703 +EDGE3 2145 2194 -6.16123 -2.45199 -1.39543 -0.00397966 0.00478315 -0.120256 +EDGE3 2145 2196 -6.40247 2.40632 -1.43996 0.00673291 -0.0035812 0.120468 +EDGE3 2146 2195 -6.15134 -2.45205 -1.37734 -0.00554773 0.00230355 -0.117139 +EDGE3 2147 2197 -6.14246 0.00655082 -1.38848 0.00463948 0.000769383 0.00365289 +EDGE3 2146 2197 -6.38223 2.40253 -1.42925 0.00349251 -0.00279098 0.124835 +EDGE3 2147 2196 -6.14631 -2.40903 -1.37557 0.00310143 -0.00497783 -0.115797 +EDGE3 2148 2198 -6.11874 -0.00852451 -1.38781 -0.00247982 0.00334181 -0.0107674 +EDGE3 2147 2198 -6.41417 2.36241 -1.436 0.00198569 -0.00842032 0.122813 +EDGE3 2148 2197 -6.14889 -2.37743 -1.3569 -0.00182153 -0.0016591 -0.122868 +EDGE3 2149 2199 -6.13725 0.00467317 -1.38531 -0.0020732 -0.00170083 0.000104444 +EDGE3 2148 2199 -6.41574 2.36567 -1.40254 -0.00460387 -0.00190647 0.122777 +EDGE3 2149 2198 -6.16 -2.36539 -1.34615 -0.000799026 0.00527669 -0.12699 diff --git a/examples/Data/ttpy10.feat b/examples/Data/ttpy10.feat deleted file mode 100644 index 265c3dfde..000000000 --- a/examples/Data/ttpy10.feat +++ /dev/null @@ -1,8 +0,0 @@ -7 -6 424 190 -4 399.553 240.574 -2 422.974 248.632 -5 480.082 258.082 -3 496.146 264.634 -0 399.5 299.5 -1 475.915 317.106 diff --git a/examples/Data/ttpy10.pose b/examples/Data/ttpy10.pose deleted file mode 100644 index b9226c723..000000000 --- a/examples/Data/ttpy10.pose +++ /dev/null @@ -1,4 +0,0 @@ -0.93969 0.24185 -0.24185 34.202 -0.34202 -0.66446 0.66446 -93.969 -0 -0.70711 -0.70711 100 -0 0 0 1 diff --git a/examples/Data/ttpy100.feat b/examples/Data/ttpy100.feat deleted file mode 100644 index fb16b2777..000000000 --- a/examples/Data/ttpy100.feat +++ /dev/null @@ -1,8 +0,0 @@ -7 -5 321.545 223.591 -4 399.553 240.574 -1 325.395 282.512 -6 372.434 296.453 -0 399.5 299.5 -3 296.479 336.708 -2 373.796 355.347 diff --git a/examples/Data/ttpy100.pose b/examples/Data/ttpy100.pose deleted file mode 100644 index cbd21233f..000000000 --- a/examples/Data/ttpy100.pose +++ /dev/null @@ -1,4 +0,0 @@ --0.93969 -0.24185 0.24185 -34.202 --0.34202 0.66446 -0.66446 93.969 -0 -0.70711 -0.70711 100 -0 0 0 1 diff --git a/examples/Data/ttpy20.feat b/examples/Data/ttpy20.feat deleted file mode 100644 index 0afb761b9..000000000 --- a/examples/Data/ttpy20.feat +++ /dev/null @@ -1,8 +0,0 @@ -7 -6 448.854 198.317 -4 399.574 240.532 -2 446.39 257.049 -5 467.479 276.146 -3 509.674 289.86 -0 399.5 299.5 -1 463.827 335.115 diff --git a/examples/Data/ttpy20.pose b/examples/Data/ttpy20.pose deleted file mode 100644 index bba2606d0..000000000 --- a/examples/Data/ttpy20.pose +++ /dev/null @@ -1,4 +0,0 @@ -0.76604 0.45452 -0.45452 64.279 -0.64279 -0.54168 0.54168 -76.604 -0 -0.70711 -0.70711 100 -0 0 0 1 diff --git a/examples/Data/ttpy30.feat b/examples/Data/ttpy30.feat deleted file mode 100644 index 412417476..000000000 --- a/examples/Data/ttpy30.feat +++ /dev/null @@ -1,8 +0,0 @@ -7 -6 468.239 211.826 -4 399.319 240.617 -2 464.725 270.725 -5 445.7 290.2 -0 399.5 299.5 -3 510.239 317.674 -1 443.471 349.078 diff --git a/examples/Data/ttpy30.pose b/examples/Data/ttpy30.pose deleted file mode 100644 index 737e391f2..000000000 --- a/examples/Data/ttpy30.pose +++ /dev/null @@ -1,4 +0,0 @@ -0.5 0.61237 -0.61237 86.603 -0.86603 -0.35355 0.35355 -50 -0 -0.70711 -0.70711 100 -0 0 0 1 diff --git a/examples/Data/ttpy40.feat b/examples/Data/ttpy40.feat deleted file mode 100644 index 0e298272b..000000000 --- a/examples/Data/ttpy40.feat +++ /dev/null @@ -1,8 +0,0 @@ -7 -6 480.111 229.111 -4 399.556 240.556 -2 476.163 287.93 -5 417.685 298.056 -0 399.605 299.535 -3 497.1 344.3 -1 416.846 357.038 diff --git a/examples/Data/ttpy40.pose b/examples/Data/ttpy40.pose deleted file mode 100644 index 4e241c130..000000000 --- a/examples/Data/ttpy40.pose +++ /dev/null @@ -1,4 +0,0 @@ -0.17365 0.69636 -0.69636 98.481 -0.98481 -0.12279 0.12279 -17.365 -0 -0.70711 -0.70711 100 -0 0 0 1 diff --git a/examples/Data/ttpy50.feat b/examples/Data/ttpy50.feat deleted file mode 100644 index 5ec007888..000000000 --- a/examples/Data/ttpy50.feat +++ /dev/null @@ -1,8 +0,0 @@ -7 -4 399.429 240.551 -6 482.812 248.312 -5 387.364 298.964 -0 399.578 299.556 -2 478.63 307.391 -1 387.98 357.804 -3 470.922 366.471 diff --git a/examples/Data/ttpy50.pose b/examples/Data/ttpy50.pose deleted file mode 100644 index 5a57b10ef..000000000 --- a/examples/Data/ttpy50.pose +++ /dev/null @@ -1,4 +0,0 @@ --0.17365 0.69636 -0.69636 98.481 -0.98481 0.12279 -0.12279 17.365 -0 -0.70711 -0.70711 100 -0 0 0 1 diff --git a/examples/Data/ttpy60.feat b/examples/Data/ttpy60.feat deleted file mode 100644 index 05237171f..000000000 --- a/examples/Data/ttpy60.feat +++ /dev/null @@ -1,8 +0,0 @@ -7 -4 399.478 240.565 -6 474.941 267.451 -5 358.473 292.364 -0 399.5 299.5 -2 471.043 326.447 -1 360.68 351.22 -3 434.473 380.709 diff --git a/examples/Data/ttpy60.pose b/examples/Data/ttpy60.pose deleted file mode 100644 index 4e5455a0d..000000000 --- a/examples/Data/ttpy60.pose +++ /dev/null @@ -1,4 +0,0 @@ --0.5 0.61237 -0.61237 86.603 -0.86603 0.35355 -0.35355 50 -0 -0.70711 -0.70711 100 -0 0 0 1 diff --git a/examples/Data/ttpy70.feat b/examples/Data/ttpy70.feat deleted file mode 100644 index fd5af8c99..000000000 --- a/examples/Data/ttpy70.feat +++ /dev/null @@ -1,8 +0,0 @@ -7 -4 399.553 240.617 -5 335.294 279.275 -6 457.717 283.698 -0 399.5 299.5 -1 338.531 338.265 -2 454.54 342.64 -3 393.218 384.691 diff --git a/examples/Data/ttpy70.pose b/examples/Data/ttpy70.pose deleted file mode 100644 index 608e9ff7c..000000000 --- a/examples/Data/ttpy70.pose +++ /dev/null @@ -1,4 +0,0 @@ --0.76604 0.45452 -0.45452 64.279 -0.64279 0.54168 -0.54168 76.604 -0 -0.70711 -0.70711 100 -0 0 0 1 diff --git a/examples/Data/ttpy80.feat b/examples/Data/ttpy80.feat deleted file mode 100644 index 465f80804..000000000 --- a/examples/Data/ttpy80.feat +++ /dev/null @@ -1,8 +0,0 @@ -7 -4 399.5 240.5 -5 320.667 261.958 -6 432.389 295.111 -0 399.5 299.5 -1 324.653 320.898 -2 430.5 353.96 -3 352.737 377.474 diff --git a/examples/Data/ttpy80.pose b/examples/Data/ttpy80.pose deleted file mode 100644 index 8a6ae4cd1..000000000 --- a/examples/Data/ttpy80.pose +++ /dev/null @@ -1,4 +0,0 @@ --0.93969 0.24185 -0.24185 34.202 -0.34202 0.66446 -0.66446 93.969 -0 -0.70711 -0.70711 100 -0 0 0 1 diff --git a/examples/Data/ttpy90.feat b/examples/Data/ttpy90.feat deleted file mode 100644 index 6731831c0..000000000 --- a/examples/Data/ttpy90.feat +++ /dev/null @@ -1,8 +0,0 @@ -7 -4 399.5 240.5 -5 316 242.5 -0 397 299.5 -6 402.765 299.588 -1 320.5 301.5 -2 402.5 358.5 -3 319 360.5 diff --git a/examples/Data/ttpy90.pose b/examples/Data/ttpy90.pose deleted file mode 100644 index 863f71fea..000000000 --- a/examples/Data/ttpy90.pose +++ /dev/null @@ -1,4 +0,0 @@ --1 -0 0 0 -0 0.70711 -0.70711 100 -0 -0.70711 -0.70711 100 -0 0 0 1 diff --git a/examples/Data/w100-odom.graph b/examples/Data/w100-odom.graph new file mode 100644 index 000000000..a88d18741 --- /dev/null +++ b/examples/Data/w100-odom.graph @@ -0,0 +1,440 @@ +VERTEX2 0 0 0 0 +VERTEX2 1 0.995595 0.0837204 0.0146728 +VERTEX2 2 2.0463 0.0352563 -0.0332615 +VERTEX2 3 3.01173 0.00117694 -0.0153904 +VERTEX2 4 4.00973 -0.0790194 -0.02875 +VERTEX2 5 5.0196 -0.0664912 -0.039715 +VERTEX2 6 5.02744 0.934341 1.51768 +VERTEX2 7 5.04775 1.89323 1.51033 +VERTEX2 8 5.15306 2.87418 1.49866 +VERTEX2 9 5.22304 3.87497 1.48364 +VERTEX2 10 5.23596 4.87041 1.47951 +VERTEX2 11 4.24581 4.94796 2.99944 +VERTEX2 12 3.22758 5.09551 2.99492 +VERTEX2 13 2.19142 5.16887 2.98707 +VERTEX2 14 1.1311 5.24329 2.97244 +VERTEX2 15 0.158988 5.30427 2.95438 +VERTEX2 16 -0.12526 4.26995 -1.76551 +VERTEX2 17 -0.25431 3.29165 -1.77099 +VERTEX2 18 -0.413555 2.30595 -1.76019 +VERTEX2 19 -0.536073 1.30685 -1.75991 +VERTEX2 20 -0.808468 0.302589 -1.76466 +VERTEX2 21 0.165652 0.0941948 -0.204681 +VERTEX2 22 1.09464 -0.0109951 -0.196319 +VERTEX2 23 2.15691 -0.187264 -0.20809 +VERTEX2 24 3.19115 -0.448207 -0.192611 +VERTEX2 25 4.13241 -0.636131 -0.162687 +VERTEX2 26 4.34104 0.512161 1.44413 +VERTEX2 27 4.44536 1.59548 1.42312 +VERTEX2 28 4.57241 2.60423 1.37618 +VERTEX2 29 4.86591 3.53433 1.35616 +VERTEX2 30 5.11392 4.4801 1.35985 +VERTEX2 31 4.21358 4.6527 2.91174 +VERTEX2 32 3.22654 4.82431 2.94929 +VERTEX2 33 2.23774 5.00761 2.97485 +VERTEX2 34 1.22736 5.20153 2.98412 +VERTEX2 35 0.123255 5.26802 2.9767 +VERTEX2 36 0.00632935 4.33864 -1.76346 +VERTEX2 37 -0.10879 3.36173 -1.7901 +VERTEX2 38 -0.321951 2.4384 -1.78648 +VERTEX2 39 -0.543773 1.34377 -1.77905 +VERTEX2 40 -0.658597 0.382801 -1.78632 +VERTEX2 41 0.317835 0.0716759 -0.235552 +VERTEX2 42 1.3002 -0.181376 -0.217406 +VERTEX2 43 2.34947 -0.372484 -0.22532 +VERTEX2 44 3.34502 -0.63322 -0.236028 +VERTEX2 45 4.3567 -0.866613 -0.24513 +VERTEX2 46 4.61743 0.074884 1.32649 +VERTEX2 47 4.7283 1.10386 1.31325 +VERTEX2 48 4.88942 2.06218 1.34353 +VERTEX2 49 5.1224 3.05224 1.34 +VERTEX2 50 5.37031 3.89715 1.33962 +VERTEX2 51 4.40295 4.12271 2.91276 +VERTEX2 52 3.40284 4.39024 2.9116 +VERTEX2 53 2.43673 4.61578 2.93887 +VERTEX2 54 1.51408 4.75597 2.91757 +VERTEX2 55 0.505735 4.96923 2.92324 +VERTEX2 56 0.256695 4.01175 -1.78543 +VERTEX2 57 0.0116126 2.99092 -1.79932 +VERTEX2 58 -0.153788 2.07052 -1.80614 +VERTEX2 59 -0.31455 1.12993 -1.83961 +VERTEX2 60 -0.593175 0.109086 -1.83163 +VERTEX2 61 -1.51899 0.241119 2.87633 +VERTEX2 62 -2.44041 0.564876 2.86065 +VERTEX2 63 -3.38567 0.881461 2.88557 +VERTEX2 64 -4.33636 1.15673 2.87003 +VERTEX2 65 -5.3523 1.33309 2.88766 +VERTEX2 66 -5.08987 2.28075 1.31311 +VERTEX2 67 -4.8429 3.23082 1.32403 +VERTEX2 68 -4.59105 4.20251 1.31499 +VERTEX2 69 -4.38824 5.10708 1.32873 +VERTEX2 70 -4.13462 5.98725 1.31402 +VERTEX2 71 -5.15517 6.29412 2.90024 +VERTEX2 72 -6.16852 6.57768 2.91315 +VERTEX2 73 -7.19212 6.7759 2.90733 +VERTEX2 74 -8.19083 6.96321 2.87753 +VERTEX2 75 -9.21776 7.31653 2.85231 +VERTEX2 76 -9.46536 6.44658 -1.86253 +VERTEX2 77 -9.70116 5.60413 -1.86719 +VERTEX2 78 -10.0031 4.63377 -1.8642 +VERTEX2 79 -10.2892 3.70939 -1.85209 +VERTEX2 80 -10.5468 2.73555 -1.86536 +VERTEX2 81 -9.53131 2.42844 -0.348286 +VERTEX2 82 -8.67728 2.03155 -0.326912 +VERTEX2 83 -7.76543 1.7035 -0.340149 +VERTEX2 84 -6.72871 1.23422 -0.332391 +VERTEX2 85 -5.7871 0.960473 -0.298466 +VERTEX2 86 -6.15287 -0.0181319 -1.84594 +VERTEX2 87 -6.48069 -0.957942 -1.82387 +VERTEX2 88 -6.74441 -1.90271 -1.83019 +VERTEX2 89 -6.98263 -2.8633 -1.82672 +VERTEX2 90 -7.25581 -3.79723 -1.7991 +VERTEX2 91 -6.24938 -3.97274 -0.228747 +VERTEX2 92 -5.2193 -4.22592 -0.231118 +VERTEX2 93 -4.2791 -4.41808 -0.244412 +VERTEX2 94 -3.27605 -4.63989 -0.262869 +VERTEX2 95 -2.21195 -4.90921 -0.241867 +VERTEX2 96 -1.9446 -3.94139 1.35224 +VERTEX2 97 -1.7284 -2.88069 1.34979 +VERTEX2 98 -1.4787 -1.9068 1.36613 +VERTEX2 99 -1.32193 -0.941704 1.35348 +EDGE2 1 0 -0.99879 0.0417574 -0.00818381 1 0 1 1 0 0 +EDGE2 2 1 -1.00336 0.0235924 -0.0056968 1 0 1 1 0 0 +EDGE2 3 2 -0.972181 0.0502932 -0.0342992 1 0 1 1 0 0 +EDGE2 4 3 -1.03801 0.00907053 -0.0116629 1 0 1 1 0 0 +EDGE2 5 4 -0.993225 0.0522372 0.00915452 1 0 1 1 0 0 +EDGE2 6 5 -1.1127 0.00877534 -1.55251 1 0 1 1 0 0 +EDGE2 7 6 -1.02681 0.0465162 -0.0118557 1 0 1 1 0 0 +EDGE2 8 7 -0.917358 0.0291951 -0.0343225 1 0 1 1 0 0 +EDGE2 9 8 -1.05727 -0.00948761 -0.0459367 1 0 1 1 0 0 +EDGE2 10 9 -0.989284 0.0306925 -0.000322391 1 0 1 1 0 0 +EDGE2 11 10 -0.997544 0.0340262 -1.59025 1 0 1 1 0 0 +EDGE2 12 11 -0.900141 -0.0311005 0.0198686 1 0 1 1 0 0 +EDGE2 13 12 -0.934983 -0.0793681 -0.00127435 1 0 1 1 0 0 +EDGE2 14 13 -0.885324 -0.0619103 0.0131666 1 0 1 1 0 0 +EDGE2 15 14 -0.90106 -0.0376226 -0.0082473 1 0 1 1 0 0 +EDGE2 16 15 -0.992517 0.00499859 -1.61534 1 0 1 1 0 0 +EDGE2 17 16 -0.975795 0.00721342 -0.00783327 1 0 1 1 0 0 +EDGE2 18 17 -0.997573 0.0333984 0.0275033 1 0 1 1 0 0 +EDGE2 19 18 -1.01687 0.04722 -0.0197328 1 0 1 1 0 0 +EDGE2 19 0 0.973663 0.0205486 1.57776 1 0 1 1 0 0 +EDGE2 20 19 -1.02103 0.00401273 0.0118729 1 0 1 1 0 0 +EDGE2 20 1 0.050153 0.95087 1.5776 1 0 1 1 0 0 +EDGE2 20 0 0.0746671 0.0345259 1.54892 1 0 1 1 0 0 +EDGE2 21 2 1.04442 -0.0648639 0.0369546 1 0 1 1 0 0 +EDGE2 21 1 -0.060912 -0.0429049 0.0281134 1 0 1 1 0 0 +EDGE2 21 0 -1.03635 -0.0239619 0.0119243 1 0 1 1 0 0 +EDGE2 21 20 -0.993726 -0.0523398 -1.58635 1 0 1 1 0 0 +EDGE2 22 2 0.0369633 -0.0141374 0.0250929 1 0 1 1 0 0 +EDGE2 22 3 1.06863 0.0015984 0.00161736 1 0 1 1 0 0 +EDGE2 22 1 -0.998706 0.0305766 0.0318395 1 0 1 1 0 0 +EDGE2 22 21 -1.03575 -0.0195948 0.0195394 1 0 1 1 0 0 +EDGE2 23 4 1.02992 0.127035 -0.0346718 1 0 1 1 0 0 +EDGE2 23 2 -0.969735 -0.0376916 -0.00768099 1 0 1 1 0 0 +EDGE2 23 3 -0.0191715 -0.0462526 0.0191143 1 0 1 1 0 0 +EDGE2 23 22 -0.923346 0.0731681 -0.0296362 1 0 1 1 0 0 +EDGE2 24 5 0.947991 -0.0175548 -0.0253511 1 0 1 1 0 0 +EDGE2 24 4 -0.0109939 0.0915607 -0.0086247 1 0 1 1 0 0 +EDGE2 24 3 -1.14502 0.0593321 -0.00746596 1 0 1 1 0 0 +EDGE2 24 23 -1.01657 -0.115682 0.0089996 1 0 1 1 0 0 +EDGE2 25 6 -0.0597013 1.02123 1.59642 1 0 1 1 0 0 +EDGE2 25 24 -1.09573 0.0614943 0.0261947 1 0 1 1 0 0 +EDGE2 25 5 -0.0734935 -0.0017356 -0.00885563 1 0 1 1 0 0 +EDGE2 25 4 -1.00036 -0.0171662 0.0202356 1 0 1 1 0 0 +EDGE2 26 7 1.00531 0.00107148 0.0302732 1 0 1 1 0 0 +EDGE2 26 25 -0.979494 0.0230425 -1.59852 1 0 1 1 0 0 +EDGE2 26 6 -0.00315216 -0.0685196 0.0109497 1 0 1 1 0 0 +EDGE2 26 5 -0.972334 0.0191047 -1.57567 1 0 1 1 0 0 +EDGE2 27 8 0.898284 -0.0536875 0.0186598 1 0 1 1 0 0 +EDGE2 27 7 0.0724439 -0.00529359 -0.000353825 1 0 1 1 0 0 +EDGE2 27 6 -1.05569 0.0767555 -0.00615115 1 0 1 1 0 0 +EDGE2 27 26 -0.967053 0.019671 0.00377432 1 0 1 1 0 0 +EDGE2 28 9 1.01666 -0.0683645 -0.023268 1 0 1 1 0 0 +EDGE2 28 27 -0.934108 -0.101065 0.00574705 1 0 1 1 0 0 +EDGE2 28 8 0.00153443 -0.0194617 0.00533619 1 0 1 1 0 0 +EDGE2 28 7 -1.0055 -0.0583432 -0.0150068 1 0 1 1 0 0 +EDGE2 29 10 1.08105 0.00811641 -0.0127997 1 0 1 1 0 0 +EDGE2 29 9 0.000458911 -0.119207 0.0094008 1 0 1 1 0 0 +EDGE2 29 8 -1.03153 0.0730486 -0.00615654 1 0 1 1 0 0 +EDGE2 29 28 -0.967347 0.0195529 -0.0185565 1 0 1 1 0 0 +EDGE2 30 10 -0.0111261 -0.0223523 -0.0275291 1 0 1 1 0 0 +EDGE2 30 11 0.0777909 0.988987 1.57983 1 0 1 1 0 0 +EDGE2 30 29 -1.04043 0.0504065 0.0370536 1 0 1 1 0 0 +EDGE2 30 9 -0.984437 -0.00337167 0.0067686 1 0 1 1 0 0 +EDGE2 31 10 -0.988697 0.0379451 -1.55557 1 0 1 1 0 0 +EDGE2 31 30 -1.00276 -0.102334 -1.55246 1 0 1 1 0 0 +EDGE2 31 11 -0.0363097 0.0438826 0.00956678 1 0 1 1 0 0 +EDGE2 31 12 1.07396 -0.0654312 -0.012633 1 0 1 1 0 0 +EDGE2 32 31 -1.07853 -0.0168996 0.00213085 1 0 1 1 0 0 +EDGE2 32 11 -1.01502 -0.0432938 -0.0288545 1 0 1 1 0 0 +EDGE2 32 12 -0.00161924 -0.0369144 0.0119887 1 0 1 1 0 0 +EDGE2 32 13 1.04694 0.02334 -0.0125276 1 0 1 1 0 0 +EDGE2 33 32 -1.04882 -0.0552537 0.046005 1 0 1 1 0 0 +EDGE2 33 12 -1.04043 -0.0558011 -0.0162327 1 0 1 1 0 0 +EDGE2 33 13 0.0562588 0.104327 0.00415458 1 0 1 1 0 0 +EDGE2 33 14 0.977863 0.0186884 0.0127758 1 0 1 1 0 0 +EDGE2 34 33 -0.994151 0.0271125 -0.0029927 1 0 1 1 0 0 +EDGE2 34 13 -0.992533 0.0446083 0.0139962 1 0 1 1 0 0 +EDGE2 34 14 0.0338907 0.00424032 0.0260941 1 0 1 1 0 0 +EDGE2 34 15 0.967129 -0.0598619 -0.0205361 1 0 1 1 0 0 +EDGE2 35 14 -0.992147 -0.0193694 -0.0208901 1 0 1 1 0 0 +EDGE2 35 34 -0.977902 0.0673003 0.0245254 1 0 1 1 0 0 +EDGE2 35 15 0.0688948 0.0729152 -0.0423015 1 0 1 1 0 0 +EDGE2 35 16 -0.0108759 0.943493 1.58518 1 0 1 1 0 0 +EDGE2 36 35 -0.974289 -0.034236 -1.59368 1 0 1 1 0 0 +EDGE2 36 15 -1.00822 0.00249408 -1.57297 1 0 1 1 0 0 +EDGE2 36 16 -0.00217215 0.103762 -0.003117 1 0 1 1 0 0 +EDGE2 36 17 1.0238 -0.0222964 0.0129001 1 0 1 1 0 0 +EDGE2 37 36 -1.01533 -0.00862644 -0.0058424 1 0 1 1 0 0 +EDGE2 37 16 -1.01359 -0.0613493 -0.0122542 1 0 1 1 0 0 +EDGE2 37 18 1.03711 0.0426359 0.00482447 1 0 1 1 0 0 +EDGE2 37 17 -0.0242366 0.0142009 -0.00533508 1 0 1 1 0 0 +EDGE2 38 18 0.0345562 0.021662 -0.0131412 1 0 1 1 0 0 +EDGE2 38 37 -0.981448 0.0523343 -0.0417572 1 0 1 1 0 0 +EDGE2 38 17 -0.961596 0.00213889 -0.00047585 1 0 1 1 0 0 +EDGE2 38 19 1.0594 -0.0430789 0.0123265 1 0 1 1 0 0 +EDGE2 39 38 -1.04804 -0.036889 -0.0235853 1 0 1 1 0 0 +EDGE2 39 18 -1.03632 -0.0536162 0.048128 1 0 1 1 0 0 +EDGE2 39 19 0.0361672 -0.0534412 -0.00346497 1 0 1 1 0 0 +EDGE2 39 0 1.00175 0.0276332 1.57543 1 0 1 1 0 0 +EDGE2 39 20 0.964769 0.103526 -0.00735911 1 0 1 1 0 0 +EDGE2 40 39 -1.03933 0.097229 0.0136057 1 0 1 1 0 0 +EDGE2 40 19 -1.02893 -0.0692033 0.00855088 1 0 1 1 0 0 +EDGE2 40 1 0.0574661 1.07674 1.54189 1 0 1 1 0 0 +EDGE2 40 21 0.0696538 0.998274 1.58379 1 0 1 1 0 0 +EDGE2 40 0 -0.03593 0.00262297 1.5732 1 0 1 1 0 0 +EDGE2 40 20 0.0769078 -0.0463276 -0.0240456 1 0 1 1 0 0 +EDGE2 41 40 -1.07316 0.00254372 -1.56145 1 0 1 1 0 0 +EDGE2 41 2 0.97152 -0.00150084 -0.0165972 1 0 1 1 0 0 +EDGE2 41 22 0.93936 -0.00378253 0.0077679 1 0 1 1 0 0 +EDGE2 41 1 0.0512203 -0.0531063 -0.0128993 1 0 1 1 0 0 +EDGE2 41 21 0.0969106 -0.00304953 -0.00537574 1 0 1 1 0 0 +EDGE2 41 0 -1.0034 -0.025292 -0.00388085 1 0 1 1 0 0 +EDGE2 41 20 -1.05749 0.0115896 -1.58133 1 0 1 1 0 0 +EDGE2 42 2 0.0235949 0.00811449 -0.00358233 1 0 1 1 0 0 +EDGE2 42 3 0.991071 -0.0286072 0.0236739 1 0 1 1 0 0 +EDGE2 42 23 1.05311 0.0104005 -0.00518416 1 0 1 1 0 0 +EDGE2 42 22 -0.0455836 0.0249413 -0.011739 1 0 1 1 0 0 +EDGE2 42 1 -1.01015 -0.014061 -0.0169645 1 0 1 1 0 0 +EDGE2 42 21 -0.892462 -0.0125915 0.0271967 1 0 1 1 0 0 +EDGE2 42 41 -1.03813 0.0163744 0.00425822 1 0 1 1 0 0 +EDGE2 43 24 0.932658 0.079441 0.00305436 1 0 1 1 0 0 +EDGE2 43 4 1.04656 0.04523 -0.0109827 1 0 1 1 0 0 +EDGE2 43 2 -1.01747 0.0488344 -0.00688551 1 0 1 1 0 0 +EDGE2 43 42 -0.988066 -0.0104386 0.0502105 1 0 1 1 0 0 +EDGE2 43 3 -0.0201045 -0.059931 0.0208538 1 0 1 1 0 0 +EDGE2 43 23 0.0121089 0.0411716 0.0274525 1 0 1 1 0 0 +EDGE2 43 22 -1.06541 0.00647669 -0.0152333 1 0 1 1 0 0 +EDGE2 44 43 -1.06111 -0.0138941 -0.0151349 1 0 1 1 0 0 +EDGE2 44 25 0.907841 -0.0585735 -0.0156694 1 0 1 1 0 0 +EDGE2 44 24 0.080514 0.0102301 -0.000739134 1 0 1 1 0 0 +EDGE2 44 5 0.994756 0.106482 -0.0329364 1 0 1 1 0 0 +EDGE2 44 4 0.0336562 0.0350477 -0.0134209 1 0 1 1 0 0 +EDGE2 44 3 -0.977117 0.0175205 0.0431175 1 0 1 1 0 0 +EDGE2 44 23 -0.995286 0.0403712 0.0311094 1 0 1 1 0 0 +EDGE2 45 25 0.086721 0.0210672 -0.01128 1 0 1 1 0 0 +EDGE2 45 6 -0.00964881 0.917532 1.58991 1 0 1 1 0 0 +EDGE2 45 26 -0.107945 1.00294 1.60674 1 0 1 1 0 0 +EDGE2 45 24 -1.06401 0.0985536 0.00301256 1 0 1 1 0 0 +EDGE2 45 44 -1.11052 0.0279259 0.0194036 1 0 1 1 0 0 +EDGE2 45 5 0.00693003 -0.107152 0.0347982 1 0 1 1 0 0 +EDGE2 45 4 -0.975055 0.00541385 0.00019082 1 0 1 1 0 0 +EDGE2 46 27 0.957182 -0.0308347 0.0232143 1 0 1 1 0 0 +EDGE2 46 7 1.08788 0.0127277 -0.00918705 1 0 1 1 0 0 +EDGE2 46 25 -1.07359 0.0262712 -1.59817 1 0 1 1 0 0 +EDGE2 46 6 0.0251908 0.0703469 -0.0114448 1 0 1 1 0 0 +EDGE2 46 26 -0.0555992 -0.0169743 -0.0141156 1 0 1 1 0 0 +EDGE2 46 45 -1.06391 0.0367663 -1.53 1 0 1 1 0 0 +EDGE2 46 5 -0.997558 0.013946 -1.56515 1 0 1 1 0 0 +EDGE2 47 27 -0.00659155 0.0206818 0.0308512 1 0 1 1 0 0 +EDGE2 47 8 0.932297 0.0905773 0.0189001 1 0 1 1 0 0 +EDGE2 47 28 1.01628 -0.0421346 0.06175 1 0 1 1 0 0 +EDGE2 47 7 -0.0838918 0.100573 -0.00623043 1 0 1 1 0 0 +EDGE2 47 6 -1.09254 -3.79076e-05 0.00973934 1 0 1 1 0 0 +EDGE2 47 26 -0.969367 0.0109812 0.0193835 1 0 1 1 0 0 +EDGE2 47 46 -0.968302 -0.0552186 0.0358645 1 0 1 1 0 0 +EDGE2 48 29 1.07313 -0.148712 0.00196928 1 0 1 1 0 0 +EDGE2 48 9 1.0849 0.0223434 0.00590472 1 0 1 1 0 0 +EDGE2 48 27 -0.914726 -0.0647734 -0.0173613 1 0 1 1 0 0 +EDGE2 48 8 0.0426816 -0.042649 -0.0177828 1 0 1 1 0 0 +EDGE2 48 28 0.0379321 -0.0109102 -0.0102417 1 0 1 1 0 0 +EDGE2 48 47 -1.06887 -0.0121303 -0.0489097 1 0 1 1 0 0 +EDGE2 48 7 -0.965107 -0.034685 -0.000290141 1 0 1 1 0 0 +EDGE2 49 10 1.12226 -0.0111233 -0.007791 1 0 1 1 0 0 +EDGE2 49 30 0.989907 -0.0123868 0.019701 1 0 1 1 0 0 +EDGE2 49 29 -0.0472499 0.0649252 -0.0229459 1 0 1 1 0 0 +EDGE2 49 9 -0.0543329 0.00135195 0.015534 1 0 1 1 0 0 +EDGE2 49 8 -0.989154 0.0177114 -0.00459804 1 0 1 1 0 0 +EDGE2 49 28 -0.904061 0.0569324 0.0300751 1 0 1 1 0 0 +EDGE2 49 48 -0.973676 0.051129 -0.0317589 1 0 1 1 0 0 +EDGE2 50 31 0.0033669 0.916796 1.58905 1 0 1 1 0 0 +EDGE2 50 10 -0.0446702 0.0139044 -0.0111686 1 0 1 1 0 0 +EDGE2 50 30 0.000176756 0.0422134 0.00416723 1 0 1 1 0 0 +EDGE2 50 11 0.0535292 0.975834 1.58092 1 0 1 1 0 0 +EDGE2 50 29 -0.944412 -0.113794 -0.0170506 1 0 1 1 0 0 +EDGE2 50 49 -1.02827 0.0163842 -0.0269791 1 0 1 1 0 0 +EDGE2 50 9 -0.979417 -0.0710258 -0.00133216 1 0 1 1 0 0 +EDGE2 51 31 -0.0518575 0.0249306 -0.00251684 1 0 1 1 0 0 +EDGE2 51 10 -1.07854 0.0248414 -1.59534 1 0 1 1 0 0 +EDGE2 51 30 -1.03347 0.0253831 -1.58701 1 0 1 1 0 0 +EDGE2 51 50 -1.04958 0.0503268 -1.58131 1 0 1 1 0 0 +EDGE2 51 32 1.00485 0.0028486 0.0195914 1 0 1 1 0 0 +EDGE2 51 11 0.0349253 -0.0171134 0.00953402 1 0 1 1 0 0 +EDGE2 51 12 1.00549 0.0628512 -0.0162726 1 0 1 1 0 0 +EDGE2 52 31 -0.982801 -0.0303748 -0.00113303 1 0 1 1 0 0 +EDGE2 52 51 -0.953712 -0.0847509 0.00541592 1 0 1 1 0 0 +EDGE2 52 32 -0.0729728 -0.0432622 0.0151166 1 0 1 1 0 0 +EDGE2 52 11 -0.994905 -0.0296327 -0.0114404 1 0 1 1 0 0 +EDGE2 52 12 -0.108004 -0.0318606 0.0170936 1 0 1 1 0 0 +EDGE2 52 33 0.918793 0.0285272 0.00925295 1 0 1 1 0 0 +EDGE2 52 13 0.992951 0.0318294 -0.007191 1 0 1 1 0 0 +EDGE2 53 32 -0.986992 -0.0026008 0.00451185 1 0 1 1 0 0 +EDGE2 53 52 -0.960158 -0.0578602 0.0212446 1 0 1 1 0 0 +EDGE2 53 12 -0.938384 0.0130893 0.0177479 1 0 1 1 0 0 +EDGE2 53 33 -0.00487972 0.0802647 -0.0156472 1 0 1 1 0 0 +EDGE2 53 13 -0.0429264 -0.0121861 0.0191245 1 0 1 1 0 0 +EDGE2 53 14 0.972309 0.0374106 -0.0227226 1 0 1 1 0 0 +EDGE2 53 34 0.920651 -0.0381205 0.00156026 1 0 1 1 0 0 +EDGE2 54 35 1.02746 -0.0232173 -0.00733268 1 0 1 1 0 0 +EDGE2 54 53 -1.03388 0.0605877 -0.0242274 1 0 1 1 0 0 +EDGE2 54 33 -0.953977 -0.0238591 0.0112294 1 0 1 1 0 0 +EDGE2 54 13 -1.01876 0.000850867 0.023767 1 0 1 1 0 0 +EDGE2 54 14 0.0142706 0.0568535 0.0156199 1 0 1 1 0 0 +EDGE2 54 34 0.029565 0.110446 -0.0176974 1 0 1 1 0 0 +EDGE2 54 15 1.08373 0.101394 0.0117167 1 0 1 1 0 0 +EDGE2 55 35 -0.0483156 -0.0176008 0.0190501 1 0 1 1 0 0 +EDGE2 55 54 -1.05102 -0.0108082 -0.0129526 1 0 1 1 0 0 +EDGE2 55 14 -1.00768 0.0938761 0.0063347 1 0 1 1 0 0 +EDGE2 55 34 -1.01362 0.020014 -0.00713884 1 0 1 1 0 0 +EDGE2 55 15 0.0386252 0.0479351 -0.000568738 1 0 1 1 0 0 +EDGE2 55 36 -0.00378631 0.992718 1.59098 1 0 1 1 0 0 +EDGE2 55 16 0.0886423 1.02733 1.62359 1 0 1 1 0 0 +EDGE2 56 35 -0.974585 -0.0699549 -1.57271 1 0 1 1 0 0 +EDGE2 56 55 -1.05595 -0.00465349 -1.60392 1 0 1 1 0 0 +EDGE2 56 15 -0.928016 -0.00655726 -1.55364 1 0 1 1 0 0 +EDGE2 56 36 0.0437675 -0.00458342 -0.011688 1 0 1 1 0 0 +EDGE2 56 16 0.024268 -0.090309 -0.00528886 1 0 1 1 0 0 +EDGE2 56 37 0.949795 -0.0460936 0.0143859 1 0 1 1 0 0 +EDGE2 56 17 0.962006 0.0477689 -0.00212384 1 0 1 1 0 0 +EDGE2 57 36 -1.08411 0.0570905 -0.015367 1 0 1 1 0 0 +EDGE2 57 56 -0.983438 -0.000514897 -0.005883 1 0 1 1 0 0 +EDGE2 57 16 -0.973679 0.00432404 -0.00761843 1 0 1 1 0 0 +EDGE2 57 38 0.907871 -0.109092 -0.00238144 1 0 1 1 0 0 +EDGE2 57 18 1.00501 0.0775972 0.00722838 1 0 1 1 0 0 +EDGE2 57 37 0.00880416 -0.0508718 0.0130591 1 0 1 1 0 0 +EDGE2 57 17 0.000245102 0.0241579 0.0127276 1 0 1 1 0 0 +EDGE2 58 57 -0.991164 0.0516127 0.0222056 1 0 1 1 0 0 +EDGE2 58 38 -0.0687829 0.0653377 -0.00943642 1 0 1 1 0 0 +EDGE2 58 18 -0.0626875 -0.108306 -0.00969368 1 0 1 1 0 0 +EDGE2 58 37 -0.941803 0.0279259 0.0445915 1 0 1 1 0 0 +EDGE2 58 17 -1.05002 -0.0131603 -0.0219704 1 0 1 1 0 0 +EDGE2 58 39 0.902028 -0.0456874 0.0293116 1 0 1 1 0 0 +EDGE2 58 19 1.05936 0.100124 -0.010211 1 0 1 1 0 0 +EDGE2 59 38 -1.02644 -0.0343746 0.00425898 1 0 1 1 0 0 +EDGE2 59 58 -0.850528 -0.00749867 0.0421351 1 0 1 1 0 0 +EDGE2 59 18 -0.885152 0.00873652 -0.00819438 1 0 1 1 0 0 +EDGE2 59 39 -0.0649969 -0.0533229 -0.0304834 1 0 1 1 0 0 +EDGE2 59 19 0.0817007 0.0632502 -0.00511583 1 0 1 1 0 0 +EDGE2 59 40 1.00694 -0.114722 0.0220379 1 0 1 1 0 0 +EDGE2 59 0 0.937874 0.0125331 1.55639 1 0 1 1 0 0 +EDGE2 59 20 0.983498 0.0680913 -0.0101281 1 0 1 1 0 0 +EDGE2 60 59 -1.0258 -0.02312 0.0206348 1 0 1 1 0 0 +EDGE2 60 39 -0.871643 -0.0291038 0.00245518 1 0 1 1 0 0 +EDGE2 60 19 -0.991389 -0.0174307 0.00265999 1 0 1 1 0 0 +EDGE2 60 40 -0.0639512 0.0351714 0.00972188 1 0 1 1 0 0 +EDGE2 60 1 0.0945945 0.903081 1.5947 1 0 1 1 0 0 +EDGE2 60 21 -0.0395067 0.984867 1.57746 1 0 1 1 0 0 +EDGE2 60 41 -0.0961783 1.01885 1.59479 1 0 1 1 0 0 +EDGE2 60 0 0.0351455 -0.0494314 1.58969 1 0 1 1 0 0 +EDGE2 60 20 -0.10896 0.00568799 -0.00742316 1 0 1 1 0 0 +EDGE2 61 40 -1.02371 -0.0384713 1.56846 1 0 1 1 0 0 +EDGE2 61 60 -1.00157 0.013005 1.56099 1 0 1 1 0 0 +EDGE2 61 0 -0.999539 -0.0815131 -3.11522 1 0 1 1 0 0 +EDGE2 61 20 -1.05417 -0.0432731 1.57241 1 0 1 1 0 0 +EDGE2 62 61 -1.06614 -0.0518437 0.0210032 1 0 1 1 0 0 +EDGE2 63 62 -1.00226 0.0602444 0.013051 1 0 1 1 0 0 +EDGE2 64 63 -1.04961 0.0446695 0.0205524 1 0 1 1 0 0 +EDGE2 65 64 -1.01538 -0.0917619 -0.00399046 1 0 1 1 0 0 +EDGE2 66 65 -1.06092 -0.0548153 1.59301 1 0 1 1 0 0 +EDGE2 67 66 -1.01683 -0.0120376 -0.0043823 1 0 1 1 0 0 +EDGE2 68 67 -1.00712 -0.0263215 -0.00660172 1 0 1 1 0 0 +EDGE2 69 68 -1.02908 0.012488 -0.0426752 1 0 1 1 0 0 +EDGE2 70 69 -0.933982 0.0175617 -0.00804355 1 0 1 1 0 0 +EDGE2 71 70 -0.951899 0.105287 -1.5595 1 0 1 1 0 0 +EDGE2 72 71 -0.990263 -0.0891221 -0.0303282 1 0 1 1 0 0 +EDGE2 73 72 -1.00818 0.0534858 0.0341473 1 0 1 1 0 0 +EDGE2 74 73 -0.927587 0.0355366 0.0278978 1 0 1 1 0 0 +EDGE2 75 74 -1.00835 0.0200616 -0.00325495 1 0 1 1 0 0 +EDGE2 76 75 -0.911527 -0.0580256 -1.56211 1 0 1 1 0 0 +EDGE2 77 76 -1.0866 -0.0563987 -0.0305906 1 0 1 1 0 0 +EDGE2 78 77 -1.02909 0.0703149 0.0223702 1 0 1 1 0 0 +EDGE2 79 78 -1.0709 0.00915469 0.0140786 1 0 1 1 0 0 +EDGE2 80 79 -1.02792 0.0686446 0.027726 1 0 1 1 0 0 +EDGE2 81 80 -0.959181 -0.0396398 -1.571 1 0 1 1 0 0 +EDGE2 82 81 -1.04191 0.0577756 0.00427146 1 0 1 1 0 0 +EDGE2 83 82 -0.936917 -0.0584888 0.00552186 1 0 1 1 0 0 +EDGE2 84 65 0.951358 0.0212743 -3.15858 1 0 1 1 0 0 +EDGE2 84 83 -1.01061 -0.0528576 -0.0203836 1 0 1 1 0 0 +EDGE2 85 65 0.124357 0.0505873 -3.15701 1 0 1 1 0 0 +EDGE2 85 66 -0.0270947 1.02244 1.57347 1 0 1 1 0 0 +EDGE2 85 64 1.02493 0.016563 -3.16695 1 0 1 1 0 0 +EDGE2 85 84 -0.987886 0.00451597 0.00269797 1 0 1 1 0 0 +EDGE2 86 65 -1.02735 -0.0704468 -1.56691 1 0 1 1 0 0 +EDGE2 86 85 -0.972762 -0.0528197 1.57225 1 0 1 1 0 0 +EDGE2 87 86 -0.91883 0.0375303 -0.0123346 1 0 1 1 0 0 +EDGE2 88 87 -1.08097 -0.104538 0.0061549 1 0 1 1 0 0 +EDGE2 89 88 -1.00986 -0.0113462 -0.00742318 1 0 1 1 0 0 +EDGE2 90 89 -1.03219 -0.0165154 -0.00181226 1 0 1 1 0 0 +EDGE2 91 90 -0.940739 0.0240986 -1.5619 1 0 1 1 0 0 +EDGE2 92 91 -1.15555 -0.0727788 -0.00855884 1 0 1 1 0 0 +EDGE2 93 92 -1.04254 0.083779 0.034681 1 0 1 1 0 0 +EDGE2 94 93 -1.07811 0.0709857 -0.00287562 1 0 1 1 0 0 +EDGE2 95 94 -0.916162 0.0464945 -0.0109007 1 0 1 1 0 0 +EDGE2 96 95 -0.983042 -0.10662 -1.57228 1 0 1 1 0 0 +EDGE2 97 96 -0.933411 0.024514 0.0124052 1 0 1 1 0 0 +EDGE2 98 97 -1.03384 0.0366015 -0.00108394 1 0 1 1 0 0 +EDGE2 99 40 0.949815 -0.0200951 -3.15597 1 0 1 1 0 0 +EDGE2 99 60 0.982217 0.038669 -3.1331 1 0 1 1 0 0 +EDGE2 99 0 1.14879 0.0129747 -1.57804 1 0 1 1 0 0 +EDGE2 99 20 1.00089 0.0504254 -3.15355 1 0 1 1 0 0 +EDGE2 99 98 -1.00067 -0.053216 -0.0254751 1 0 1 1 0 0 +EQUIV 21 1 +EQUIV 22 2 +EQUIV 23 3 +EQUIV 24 4 +EQUIV 25 5 +EQUIV 26 6 +EQUIV 27 7 +EQUIV 28 8 +EQUIV 29 9 +EQUIV 30 10 +EQUIV 31 11 +EQUIV 32 12 +EQUIV 33 13 +EQUIV 34 14 +EQUIV 35 15 +EQUIV 36 16 +EQUIV 37 17 +EQUIV 38 18 +EQUIV 39 19 +EQUIV 40 20 +EQUIV 41 1 +EQUIV 42 2 +EQUIV 43 3 +EQUIV 44 4 +EQUIV 45 5 +EQUIV 46 6 +EQUIV 47 7 +EQUIV 48 8 +EQUIV 49 9 +EQUIV 50 10 +EQUIV 51 11 +EQUIV 52 12 +EQUIV 53 13 +EQUIV 54 14 +EQUIV 55 15 +EQUIV 56 16 +EQUIV 57 17 +EQUIV 58 18 +EQUIV 59 19 +EQUIV 60 20 diff --git a/examples/LocalizationExample.cpp b/examples/LocalizationExample.cpp index 2d2357dad..578f33558 100644 --- a/examples/LocalizationExample.cpp +++ b/examples/LocalizationExample.cpp @@ -35,7 +35,7 @@ using namespace gtsam; */ int main(int argc, char** argv) { - // create the graph (defined in pose2SLAM.h, derived from NonlinearFactorGraph) + // create the graph (defined in pose2SLAM.h, derived from NonlinearFactorGraph) pose2SLAM::Graph graph; // add a Gaussian prior on pose x_1 @@ -55,7 +55,7 @@ int main(int argc, char** argv) { // create (deliberatly inaccurate) initial estimate pose2SLAM::Values initialEstimate; initialEstimate.insertPose(1, Pose2(0.5, 0.0, 0.2)); - initialEstimate.insertPose(2, Pose2(2.3, 0.1,-0.2)); + initialEstimate.insertPose(2, Pose2(2.3, 0.1, -0.2)); initialEstimate.insertPose(3, Pose2(4.1, 0.1, 0.1)); initialEstimate.print("\nInitial estimate:\n "); @@ -64,11 +64,11 @@ int main(int argc, char** argv) { result.print("\nFinal result:\n "); // Query the marginals - Marginals marginals = graph.marginals(result); cout.precision(2); - cout << "\nP1:\n" << marginals.marginalCovariance(pose2SLAM::PoseKey(1)) << endl; - cout << "\nP2:\n" << marginals.marginalCovariance(pose2SLAM::PoseKey(2)) << endl; - cout << "\nP3:\n" << marginals.marginalCovariance(pose2SLAM::PoseKey(3)) << endl; + Marginals marginals = graph.marginals(result); + cout << "\nP1:\n" << marginals.marginalCovariance(1) << endl; + cout << "\nP2:\n" << marginals.marginalCovariance(2) << endl; + cout << "\nP3:\n" << marginals.marginalCovariance(3) << endl; return 0; } diff --git a/examples/LocalizationExample2.cpp b/examples/LocalizationExample2.cpp index 903101d87..9a4330181 100644 --- a/examples/LocalizationExample2.cpp +++ b/examples/LocalizationExample2.cpp @@ -71,10 +71,9 @@ int main(int argc, char** argv) { // add unary measurement factors, like GPS, on all three poses SharedDiagonal noiseModel(Vector_(2, 0.1, 0.1)); // 10cm std on x,y - Symbol x1('x',1), x2('x',2), x3('x',3); - graph.push_back(boost::make_shared(x1, 0, 0, noiseModel)); - graph.push_back(boost::make_shared(x2, 2, 0, noiseModel)); - graph.push_back(boost::make_shared(x3, 4, 0, noiseModel)); + graph.push_back(boost::make_shared(1, 0, 0, noiseModel)); + graph.push_back(boost::make_shared(2, 2, 0, noiseModel)); + graph.push_back(boost::make_shared(3, 4, 0, noiseModel)); // print graph.print("\nFactor graph:\n"); @@ -94,9 +93,9 @@ int main(int argc, char** argv) { // Query the marginals Marginals marginals(graph, result); cout.precision(2); - cout << "\nP1:\n" << marginals.marginalCovariance(x1) << endl; - cout << "\nP2:\n" << marginals.marginalCovariance(x2) << endl; - cout << "\nP3:\n" << marginals.marginalCovariance(x3) << endl; + cout << "\nP1:\n" << marginals.marginalCovariance(1) << endl; + cout << "\nP2:\n" << marginals.marginalCovariance(2) << endl; + cout << "\nP3:\n" << marginals.marginalCovariance(3) << endl; return 0; } diff --git a/examples/PlanarSLAMExample_easy.cpp b/examples/PlanarSLAMExample.cpp similarity index 75% rename from examples/PlanarSLAMExample_easy.cpp rename to examples/PlanarSLAMExample.cpp index 808de3ba3..d58c8eb3e 100644 --- a/examples/PlanarSLAMExample_easy.cpp +++ b/examples/PlanarSLAMExample.cpp @@ -18,6 +18,9 @@ // pull in the planar SLAM domain with all typedefs and helper functions defined #include +// we will use Symbol keys +#include + using namespace std; using namespace gtsam; @@ -35,16 +38,20 @@ int main(int argc, char** argv) { // create the graph (defined in planarSlam.h, derived from NonlinearFactorGraph) planarSLAM::Graph graph; + // Create some keys + static Symbol i1('x',1), i2('x',2), i3('x',3); + static Symbol j1('l',1), j2('l',2); + // add a Gaussian prior on pose x_1 Pose2 priorMean(0.0, 0.0, 0.0); // prior mean is at origin SharedDiagonal priorNoise(Vector_(3, 0.3, 0.3, 0.1)); // 30cm std on x,y, 0.1 rad on theta - graph.addPrior(1, priorMean, priorNoise); // add directly to graph + graph.addPrior(i1, priorMean, priorNoise); // add directly to graph // add two odometry factors Pose2 odometry(2.0, 0.0, 0.0); // create a measurement for both factors (the same in this case) SharedDiagonal odometryNoise(Vector_(3, 0.2, 0.2, 0.1)); // 20cm std on x,y, 0.1 rad on theta - graph.addOdometry(1, 2, odometry, odometryNoise); - graph.addOdometry(2, 3, odometry, odometryNoise); + graph.addOdometry(i1, i2, odometry, odometryNoise); + graph.addOdometry(i2, i3, odometry, odometryNoise); // create a noise model for the landmark measurements SharedDiagonal measurementNoise(Vector_(2, 0.1, 0.2)); // 0.1 rad std on bearing, 20cm on range @@ -58,20 +65,20 @@ int main(int argc, char** argv) { range32 = 2.0; // add bearing/range factors (created by "addBearingRange") - graph.addBearingRange(1, 1, bearing11, range11, measurementNoise); - graph.addBearingRange(2, 1, bearing21, range21, measurementNoise); - graph.addBearingRange(3, 2, bearing32, range32, measurementNoise); + graph.addBearingRange(i1, j1, bearing11, range11, measurementNoise); + graph.addBearingRange(i2, j1, bearing21, range21, measurementNoise); + graph.addBearingRange(i3, j2, bearing32, range32, measurementNoise); // print graph.print("Factor graph"); // create (deliberatly inaccurate) initial estimate planarSLAM::Values initialEstimate; - initialEstimate.insertPose(1, Pose2(0.5, 0.0, 0.2)); - initialEstimate.insertPose(2, Pose2(2.3, 0.1,-0.2)); - initialEstimate.insertPose(3, Pose2(4.1, 0.1, 0.1)); - initialEstimate.insertPoint(1, Point2(1.8, 2.1)); - initialEstimate.insertPoint(2, Point2(4.1, 1.8)); + initialEstimate.insertPose(i1, Pose2(0.5, 0.0, 0.2)); + initialEstimate.insertPose(i2, Pose2(2.3, 0.1,-0.2)); + initialEstimate.insertPose(i3, Pose2(4.1, 0.1, 0.1)); + initialEstimate.insertPoint(j1, Point2(1.8, 2.1)); + initialEstimate.insertPoint(j2, Point2(4.1, 1.8)); initialEstimate.print("Initial estimate:\n "); diff --git a/examples/PlanarSLAMSelfContained_advanced.cpp b/examples/PlanarSLAMExample_selfcontained.cpp similarity index 72% rename from examples/PlanarSLAMSelfContained_advanced.cpp rename to examples/PlanarSLAMExample_selfcontained.cpp index 102dcc315..53803a70f 100644 --- a/examples/PlanarSLAMSelfContained_advanced.cpp +++ b/examples/PlanarSLAMExample_selfcontained.cpp @@ -10,34 +10,34 @@ * -------------------------------------------------------------------------- */ /** - * @file PlanarSLAMSelfContained_advanced.cpp + * @file PlanarSLAMExample_selfcontained.cpp * @brief Simple robotics example with all typedefs internal to this script. * @author Alex Cunningham */ -#include -#include - -// for all nonlinear keys -#include - -// for points and poses -#include -#include - -// for modeling measurement uncertainty - all models included here -#include - // add in headers for specific factors #include #include #include +// for all nonlinear keys +#include + // implementations for structures - needed if self-contained, and these should be included last #include #include #include +// for modeling measurement uncertainty - all models included here +#include + +// for points and poses +#include +#include + +#include +#include + using namespace std; using namespace gtsam; @@ -52,26 +52,26 @@ using namespace gtsam; */ int main(int argc, char** argv) { // create keys for variables - Symbol x1('x',1), x2('x',2), x3('x',3); - Symbol l1('l',1), l2('l',2); + Symbol i1('x',1), i2('x',2), i3('x',3); + Symbol j1('l',1), j2('l',2); // create graph container and add factors to it NonlinearFactorGraph graph; /* add prior */ // gaussian for prior - SharedDiagonal prior_model = noiseModel::Diagonal::Sigmas(Vector_(3, 0.3, 0.3, 0.1)); - Pose2 prior_measurement(0.0, 0.0, 0.0); // prior at origin - PriorFactor posePrior(x1, prior_measurement, prior_model); // create the factor + SharedDiagonal priorNoise = noiseModel::Diagonal::Sigmas(Vector_(3, 0.3, 0.3, 0.1)); + Pose2 priorMean(0.0, 0.0, 0.0); // prior at origin + PriorFactor posePrior(i1, priorMean, priorNoise); // create the factor graph.add(posePrior); // add the factor to the graph /* add odometry */ // general noisemodel for odometry - SharedDiagonal odom_model = noiseModel::Diagonal::Sigmas(Vector_(3, 0.2, 0.2, 0.1)); - Pose2 odom_measurement(2.0, 0.0, 0.0); // create a measurement for both factors (the same in this case) + SharedDiagonal odometryNoise = noiseModel::Diagonal::Sigmas(Vector_(3, 0.2, 0.2, 0.1)); + Pose2 odometry(2.0, 0.0, 0.0); // create a measurement for both factors (the same in this case) // create between factors to represent odometry - BetweenFactor odom12(x1, x2, odom_measurement, odom_model); - BetweenFactor odom23(x2, x3, odom_measurement, odom_model); + BetweenFactor odom12(i1, i2, odometry, odometryNoise); + BetweenFactor odom23(i2, i3, odometry, odometryNoise); graph.add(odom12); // add both to graph graph.add(odom23); @@ -88,9 +88,9 @@ int main(int argc, char** argv) { range32 = 2.0; // create bearing/range factors - BearingRangeFactor meas11(x1, l1, bearing11, range11, meas_model); - BearingRangeFactor meas21(x2, l1, bearing21, range21, meas_model); - BearingRangeFactor meas32(x3, l2, bearing32, range32, meas_model); + BearingRangeFactor meas11(i1, j1, bearing11, range11, meas_model); + BearingRangeFactor meas21(i2, j1, bearing21, range21, meas_model); + BearingRangeFactor meas32(i3, j2, bearing32, range32, meas_model); // add the factors graph.add(meas11); @@ -101,11 +101,11 @@ int main(int argc, char** argv) { // initialize to noisy points Values initial; - initial.insert(x1, Pose2(0.5, 0.0, 0.2)); - initial.insert(x2, Pose2(2.3, 0.1,-0.2)); - initial.insert(x3, Pose2(4.1, 0.1, 0.1)); - initial.insert(l1, Point2(1.8, 2.1)); - initial.insert(l2, Point2(4.1, 1.8)); + initial.insert(i1, Pose2(0.5, 0.0, 0.2)); + initial.insert(i2, Pose2(2.3, 0.1,-0.2)); + initial.insert(i3, Pose2(4.1, 0.1, 0.1)); + initial.insert(j1, Point2(1.8, 2.1)); + initial.insert(j2, Point2(4.1, 1.8)); initial.print("initial estimate"); @@ -126,11 +126,11 @@ int main(int argc, char** argv) { // Print marginals covariances for all variables Marginals marginals(graph, resultMultifrontal, Marginals::CHOLESKY); - print(marginals.marginalCovariance(x1), "x1 covariance"); - print(marginals.marginalCovariance(x2), "x2 covariance"); - print(marginals.marginalCovariance(x3), "x3 covariance"); - print(marginals.marginalCovariance(l1), "l1 covariance"); - print(marginals.marginalCovariance(l2), "l2 covariance"); + print(marginals.marginalCovariance(i1), "i1 covariance"); + print(marginals.marginalCovariance(i2), "i2 covariance"); + print(marginals.marginalCovariance(i3), "i3 covariance"); + print(marginals.marginalCovariance(j1), "j1 covariance"); + print(marginals.marginalCovariance(j2), "j2 covariance"); return 0; } diff --git a/examples/Pose2SLAMExample_easy.cpp b/examples/Pose2SLAMExample.cpp similarity index 57% rename from examples/Pose2SLAMExample_easy.cpp rename to examples/Pose2SLAMExample.cpp index ef704c5fc..8118004af 100644 --- a/examples/Pose2SLAMExample_easy.cpp +++ b/examples/Pose2SLAMExample.cpp @@ -10,15 +10,15 @@ * -------------------------------------------------------------------------- */ /** - * @file Pose2SLAMExample_easy.cpp + * @file Pose2SLAMExample.cpp * @brief A 2D Pose SLAM example using the predefined typedefs in gtsam/slam/pose2SLAM.h * @date Oct 21, 2010 * @author Yong Dian Jian */ // pull in the Pose2 SLAM domain with all typedefs and helper functions defined -#include #include +#include using namespace std; using namespace gtsam; @@ -26,7 +26,7 @@ using namespace gtsam; int main(int argc, char** argv) { // 1. Create graph container and add factors to it - pose2SLAM::Graph graph ; + pose2SLAM::Graph graph; // 2a. Add Gaussian prior Pose2 priorMean(0.0, 0.0, 0.0); // prior at origin @@ -35,30 +35,30 @@ int main(int argc, char** argv) { // 2b. Add odometry factors SharedDiagonal odometryNoise(Vector_(3, 0.2, 0.2, 0.1)); - graph.addOdometry(1, 2, Pose2(2.0, 0.0, 0.0 ), odometryNoise); - graph.addOdometry(2, 3, Pose2(2.0, 0.0, M_PI/2.0), odometryNoise); - graph.addOdometry(3, 4, Pose2(2.0, 0.0, M_PI/2.0), odometryNoise); - graph.addOdometry(4, 5, Pose2(2.0, 0.0, M_PI/2.0), odometryNoise); + graph.addOdometry(1, 2, Pose2(2.0, 0.0, 0.0), odometryNoise); + graph.addOdometry(2, 3, Pose2(2.0, 0.0, M_PI_2), odometryNoise); + graph.addOdometry(3, 4, Pose2(2.0, 0.0, M_PI_2), odometryNoise); + graph.addOdometry(4, 5, Pose2(2.0, 0.0, M_PI_2), odometryNoise); // 2c. Add pose constraint - SharedDiagonal constraintUncertainty(Vector_(3, 0.2, 0.2, 0.1)); - graph.addConstraint(5, 2, Pose2(2.0, 0.0, M_PI/2.0), constraintUncertainty); + SharedDiagonal model(Vector_(3, 0.2, 0.2, 0.1)); + graph.addConstraint(5, 2, Pose2(2.0, 0.0, M_PI_2), model); // print graph.print("\nFactor graph:\n"); - // 3. Create the data structure to hold the initialEstimate estinmate to the solution + // 3. Create the data structure to hold the initialEstimate estimate to the solution pose2SLAM::Values initialEstimate; - Pose2 x1(0.5, 0.0, 0.2 ); initialEstimate.insertPose(1, x1); - Pose2 x2(2.3, 0.1,-0.2 ); initialEstimate.insertPose(2, x2); - Pose2 x3(4.1, 0.1, M_PI/2.0); initialEstimate.insertPose(3, x3); - Pose2 x4(4.0, 2.0, M_PI ); initialEstimate.insertPose(4, x4); - Pose2 x5(2.1, 2.1,-M_PI/2.0); initialEstimate.insertPose(5, x5); - initialEstimate.print("\nInitial estimate:\n "); + initialEstimate.insertPose(1, Pose2(0.5, 0.0, 0.2)); + initialEstimate.insertPose(2, Pose2(2.3, 0.1, -0.2)); + initialEstimate.insertPose(3, Pose2(4.1, 0.1, M_PI_2)); + initialEstimate.insertPose(4, Pose2(4.0, 2.0, M_PI)); + initialEstimate.insertPose(5, Pose2(2.1, 2.1, -M_PI_2)); + initialEstimate.print("\nInitial estimate:\n"); // 4. Single Step Optimization using Levenberg-Marquardt pose2SLAM::Values result = graph.optimize(initialEstimate); - result.print("\nFinal result:\n "); + result.print("\nFinal result:\n"); return 0; } diff --git a/examples/Pose2SLAMExample_advanced.cpp b/examples/Pose2SLAMExample_advanced.cpp index 29d8c58cf..083585c73 100644 --- a/examples/Pose2SLAMExample_advanced.cpp +++ b/examples/Pose2SLAMExample_advanced.cpp @@ -16,48 +16,41 @@ * @author Chris Beall */ -#include -#include -#include - // pull in the Pose2 SLAM domain with all typedefs and helper functions defined #include #include #include - #include #include +#include +#include +#include + using namespace std; using namespace gtsam; -using namespace boost; -using namespace pose2SLAM; int main(int argc, char** argv) { /* 1. create graph container and add factors to it */ - Graph graph; + pose2SLAM::Graph graph; /* 2.a add prior */ - // gaussian for prior - SharedDiagonal prior_model = noiseModel::Diagonal::Sigmas(Vector_(3, 0.3, 0.3, 0.1)); - Pose2 prior_measurement(0.0, 0.0, 0.0); // prior at origin - graph.addPrior(1, prior_measurement, prior_model); // add directly to graph + Pose2 priorMean(0.0, 0.0, 0.0); // prior at origin + SharedDiagonal priorNoise(Vector_(3, 0.3, 0.3, 0.1)); // 30cm std on x,y, 0.1 rad on theta + graph.addPrior(1, priorMean, priorNoise); // add directly to graph /* 2.b add odometry */ - // general noisemodel for odometry - SharedDiagonal odom_model = noiseModel::Diagonal::Sigmas(Vector_(3, 0.2, 0.2, 0.1)); - - /* Pose2 measurements take (x,y,theta), where theta is taken from the positive x-axis*/ - Pose2 odom_measurement(2.0, 0.0, 0.0); // create a measurement for both factors (the same in this case) - graph.addOdometry(1, 2, odom_measurement, odom_model); - graph.addOdometry(2, 3, odom_measurement, odom_model); + SharedDiagonal odometryNoise(Vector_(3, 0.2, 0.2, 0.1)); // 20cm std on x,y, 0.1 rad on theta + Pose2 odometry(2.0, 0.0, 0.0); // create a measurement for both factors (the same in this case) + graph.addOdometry(1, 2, odometry, odometryNoise); + graph.addOdometry(2, 3, odometry, odometryNoise); graph.print("full graph"); - /* 3. Create the data structure to hold the initial estimate to the solution - * initialize to noisy points */ + /* 3. Create the data structure to hold the initial estimate to the solution + * initialize to noisy points */ pose2SLAM::Values initial; initial.insertPose(1, Pose2(0.5, 0.0, 0.2)); - initial.insertPose(2, Pose2(2.3, 0.1,-0.2)); + initial.insertPose(2, Pose2(2.3, 0.1, -0.2)); initial.insertPose(3, Pose2(4.1, 0.1, 0.1)); initial.print("initial estimate"); @@ -70,15 +63,15 @@ int main(int argc, char** argv) { params.absoluteErrorTol = 1e-15; params.relativeErrorTol = 1e-15; params.ordering = ordering; - LevenbergMarquardtOptimizer optimizer(graph, initial, params); + LevenbergMarquardtOptimizer optimizer(graph, initial, params); pose2SLAM::Values result = optimizer.optimize(); result.print("final result"); /* Get covariances */ Marginals marginals(graph, result, Marginals::CHOLESKY); - Matrix covariance1 = marginals.marginalCovariance(PoseKey(1)); - Matrix covariance2 = marginals.marginalCovariance(PoseKey(2)); + Matrix covariance1 = marginals.marginalCovariance(1); + Matrix covariance2 = marginals.marginalCovariance(2); print(covariance1, "Covariance1"); print(covariance2, "Covariance2"); diff --git a/examples/Pose2SLAMExample_graph.cpp b/examples/Pose2SLAMExample_graph.cpp new file mode 100644 index 000000000..6abeceb55 --- /dev/null +++ b/examples/Pose2SLAMExample_graph.cpp @@ -0,0 +1,53 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file Pose2SLAMExample_graph->cpp + * @brief Read graph from file and perform GraphSLAM + * @date June 3, 2012 + * @author Frank Dellaert + */ + +#include +#include +#include +#include +#include + +using namespace std; +using namespace gtsam; + +int main(int argc, char** argv) { + + // Read File and create graph and initial estimate + // we are in build/examples, data is in examples/Data + pose2SLAM::Graph::shared_ptr graph ; + pose2SLAM::Values::shared_ptr initial; + SharedDiagonal model(Vector_(3, 0.05, 0.05, 5.0*M_PI/180.0)); + boost::tie(graph,initial) = load2D("../../examples/Data/w100-odom.graph",model); + initial->print("Initial estimate:\n"); + + // Add a Gaussian prior on first poses + Pose2 priorMean(0.0, 0.0, 0.0); // prior at origin + SharedDiagonal priorNoise(Vector_(3, 0.01, 0.01, 0.01)); + graph->addPrior(0, priorMean, priorNoise); + + // Single Step Optimization using Levenberg-Marquardt + pose2SLAM::Values result = graph->optimize(*initial); + result.print("\nFinal result:\n"); + + // Plot the covariance of the last pose + Marginals marginals(*graph, result); + cout.precision(2); + cout << "\nP3:\n" << marginals.marginalCovariance(99) << endl; + +return 0; +} diff --git a/examples/Pose2SLAMwSPCG.cpp b/examples/Pose2SLAMwSPCG.cpp new file mode 100644 index 000000000..c5c2efc66 --- /dev/null +++ b/examples/Pose2SLAMwSPCG.cpp @@ -0,0 +1,77 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file Pose2SLAMwSPCG.cpp + * @brief A 2D Pose SLAM example using the SimpleSPCGSolver. + * @author Yong-Dian Jian + * @date June 2, 2012 + */ + +#include +#include +#include + +#include +#include + +using namespace std; +using namespace gtsam; + +/* ************************************************************************* */ +int main(void) { + + // 1. Create graph container and add factors to it + pose2SLAM::Graph graph ; + + // 2a. Add Gaussian prior + Pose2 priorMean(0.0, 0.0, 0.0); // prior at origin + SharedDiagonal priorNoise(Vector_(3, 0.3, 0.3, 0.1)); + graph.addPrior(1, priorMean, priorNoise); + + // 2b. Add odometry factors + SharedDiagonal odometryNoise(Vector_(3, 0.2, 0.2, 0.1)); + graph.addOdometry(1, 2, Pose2(2.0, 0.0, 0.0 ), odometryNoise); + graph.addOdometry(2, 3, Pose2(2.0, 0.0, M_PI_2), odometryNoise); + graph.addOdometry(3, 4, Pose2(2.0, 0.0, M_PI_2), odometryNoise); + graph.addOdometry(4, 5, Pose2(2.0, 0.0, M_PI_2), odometryNoise); + + // 2c. Add pose constraint + SharedDiagonal constraintUncertainty(Vector_(3, 0.2, 0.2, 0.1)); + graph.addConstraint(5, 2, Pose2(2.0, 0.0, M_PI_2), constraintUncertainty); + + // print + graph.print("\nFactor graph:\n"); + + // 3. Create the data structure to hold the initialEstimate estinmate to the solution + pose2SLAM::Values initialEstimate; + Pose2 x1(0.5, 0.0, 0.2 ); initialEstimate.insertPose(1, x1); + Pose2 x2(2.3, 0.1,-0.2 ); initialEstimate.insertPose(2, x2); + Pose2 x3(4.1, 0.1, M_PI_2); initialEstimate.insertPose(3, x3); + Pose2 x4(4.0, 2.0, M_PI ); initialEstimate.insertPose(4, x4); + Pose2 x5(2.1, 2.1,-M_PI_2); initialEstimate.insertPose(5, x5); + initialEstimate.print("\nInitial estimate:\n "); + cout << "initial error = " << graph.error(initialEstimate) << endl ; + + // 4. Single Step Optimization using Levenberg-Marquardt + // Note: Although there are many options in IterativeOptimizationParameters, + // the SimpleSPCGSolver doesn't actually use all of them at this moment. + // More detail in the next release. + LevenbergMarquardtParams param; + param.linearSolverType = SuccessiveLinearizationParams::CG; + param.iterativeParams = boost::make_shared(); + + LevenbergMarquardtOptimizer optimizer(graph, initialEstimate, param); + Values result = optimizer.optimize(); + cout << "final error = " << graph.error(result) << endl; + + return 0 ; +} diff --git a/examples/Pose2SLAMwSPCG_advanced.cpp b/examples/Pose2SLAMwSPCG_advanced.cpp deleted file mode 100644 index 12d17a6e9..000000000 --- a/examples/Pose2SLAMwSPCG_advanced.cpp +++ /dev/null @@ -1,109 +0,0 @@ -/* ---------------------------------------------------------------------------- - - * GTSAM Copyright 2010, Georgia Tech Research Corporation, - * Atlanta, Georgia 30332-0415 - * All Rights Reserved - * Authors: Frank Dellaert, et al. (see THANKS for the full author list) - - * See LICENSE for the license information - - * -------------------------------------------------------------------------- */ - -/* - * @file Pose2SLAMwSPCG_advanced.cpp - * @brief Solve a simple 3 by 3 grid of Pose2 SLAM problem by using advanced SPCG interface - * @author Yong Dian - * Created October 21, 2010 - */ - -#include - -#if ENABLE_SPCG - -#include - -#include -#include -#include - -using namespace std; -using namespace gtsam; -using namespace pose2SLAM; - -typedef boost::shared_ptr sharedGraph ; -typedef boost::shared_ptr sharedValue ; -//typedef NonlinearOptimizer > SPCGOptimizer; - - -typedef SubgraphSolver Solver; -typedef boost::shared_ptr sharedSolver ; -typedef NonlinearOptimizer SPCGOptimizer; - -sharedGraph graph; -sharedValue initial; -Values result; - -/* ************************************************************************* */ -int main(void) { - - /* generate synthetic data */ - const SharedNoiseModel sigma(noiseModel::Unit::Create(0.1)); - Key x1(1), x2(2), x3(3), x4(4), x5(5), x6(6), x7(7), x8(8), x9(9); - - graph = boost::make_shared() ; - initial = boost::make_shared() ; - - // create a 3 by 3 grid - // x3 x6 x9 - // x2 x5 x8 - // x1 x4 x7 - graph->addConstraint(x1,x2,Pose2(0,2,0),sigma) ; - graph->addConstraint(x2,x3,Pose2(0,2,0),sigma) ; - graph->addConstraint(x4,x5,Pose2(0,2,0),sigma) ; - graph->addConstraint(x5,x6,Pose2(0,2,0),sigma) ; - graph->addConstraint(x7,x8,Pose2(0,2,0),sigma) ; - graph->addConstraint(x8,x9,Pose2(0,2,0),sigma) ; - graph->addConstraint(x1,x4,Pose2(2,0,0),sigma) ; - graph->addConstraint(x4,x7,Pose2(2,0,0),sigma) ; - graph->addConstraint(x2,x5,Pose2(2,0,0),sigma) ; - graph->addConstraint(x5,x8,Pose2(2,0,0),sigma) ; - graph->addConstraint(x3,x6,Pose2(2,0,0),sigma) ; - graph->addConstraint(x6,x9,Pose2(2,0,0),sigma) ; - graph->addPrior(x1, Pose2(0,0,0), sigma) ; - - initial->insert(x1, Pose2( 0, 0, 0)); - initial->insert(x2, Pose2( 0, 2.1, 0.01)); - initial->insert(x3, Pose2( 0, 3.9,-0.01)); - initial->insert(x4, Pose2(2.1,-0.1, 0)); - initial->insert(x5, Pose2(1.9, 2.1, 0.02)); - initial->insert(x6, Pose2(2.0, 3.9,-0.02)); - initial->insert(x7, Pose2(4.0, 0.1, 0.03 )); - initial->insert(x8, Pose2(3.9, 2.1, 0.01)); - initial->insert(x9, Pose2(4.1, 3.9,-0.01)); - /* done with generating data */ - - - graph->print("full graph") ; - initial->print("initial estimate") ; - - sharedSolver solver(new Solver(*graph, *initial)) ; - SPCGOptimizer optimizer(graph, initial, solver->ordering(), solver) ; - - cout << "before optimization, sum of error is " << optimizer.error() << endl; - SPCGOptimizer optimizer2 = optimizer.levenbergMarquardt(); - cout << "after optimization, sum of error is " << optimizer2.error() << endl; - - result = *optimizer2.values() ; - result.print("final result") ; - - return 0 ; -} - -#else - -int main() { - std::cout << "SPCG is currently disabled" << std::endl; - return 0; -} - -#endif diff --git a/examples/Pose2SLAMwSPCG_easy.cpp b/examples/Pose2SLAMwSPCG_easy.cpp deleted file mode 100644 index e610d327c..000000000 --- a/examples/Pose2SLAMwSPCG_easy.cpp +++ /dev/null @@ -1,87 +0,0 @@ -/* ---------------------------------------------------------------------------- - - * GTSAM Copyright 2010, Georgia Tech Research Corporation, - * Atlanta, Georgia 30332-0415 - * All Rights Reserved - * Authors: Frank Dellaert, et al. (see THANKS for the full author list) - - * See LICENSE for the license information - - * -------------------------------------------------------------------------- */ - -/* - * @file Pose2SLAMwSPCG_easy.cpp - * @brief Solve a simple 3 by 3 grid of Pose2 SLAM problem by using easy SPCG interface - * @author Yong Dian - * Created October 21, 2010 - */ - -#include - -#if ENABLE_SPCG - -#include - -#include -#include - - -using namespace std; -using namespace gtsam; -using namespace pose2SLAM; - -Graph graph; -Values initial, result; - -/* ************************************************************************* */ -int main(void) { - - /* generate synthetic data */ - const SharedNoiseModel sigma(noiseModel::Unit::Create(0.1)); - Key x1(1), x2(2), x3(3), x4(4), x5(5), x6(6), x7(7), x8(8), x9(9); - - // create a 3 by 3 grid - // x3 x6 x9 - // x2 x5 x8 - // x1 x4 x7 - graph.addConstraint(x1,x2,Pose2(0,2,0),sigma) ; - graph.addConstraint(x2,x3,Pose2(0,2,0),sigma) ; - graph.addConstraint(x4,x5,Pose2(0,2,0),sigma) ; - graph.addConstraint(x5,x6,Pose2(0,2,0),sigma) ; - graph.addConstraint(x7,x8,Pose2(0,2,0),sigma) ; - graph.addConstraint(x8,x9,Pose2(0,2,0),sigma) ; - graph.addConstraint(x1,x4,Pose2(2,0,0),sigma) ; - graph.addConstraint(x4,x7,Pose2(2,0,0),sigma) ; - graph.addConstraint(x2,x5,Pose2(2,0,0),sigma) ; - graph.addConstraint(x5,x8,Pose2(2,0,0),sigma) ; - graph.addConstraint(x3,x6,Pose2(2,0,0),sigma) ; - graph.addConstraint(x6,x9,Pose2(2,0,0),sigma) ; - graph.addPrior(x1, Pose2(0,0,0), sigma) ; - - initial.insert(x1, Pose2( 0, 0, 0)); - initial.insert(x2, Pose2( 0, 2.1, 0.01)); - initial.insert(x3, Pose2( 0, 3.9,-0.01)); - initial.insert(x4, Pose2(2.1,-0.1, 0)); - initial.insert(x5, Pose2(1.9, 2.1, 0.02)); - initial.insert(x6, Pose2(2.0, 3.9,-0.02)); - initial.insert(x7, Pose2(4.0, 0.1, 0.03 )); - initial.insert(x8, Pose2(3.9, 2.1, 0.01)); - initial.insert(x9, Pose2(4.1, 3.9,-0.01)); - /* done */ - - - graph.print("full graph") ; - initial.print("initial estimate"); - result = optimizeSPCG(graph, initial); - result.print("final result") ; - return 0 ; -} - -#else - -int main() { - std::cout << "SPCG is currently disabled" << std::endl; - return 0; -} - -#endif diff --git a/examples/README b/examples/README index d7706a0b8..2a54459f3 100644 --- a/examples/README +++ b/examples/README @@ -1,4 +1,4 @@ -This directory contains a number of exapmples that illustrate the use of GTSAM: +This directory contains a number of examples that illustrate the use of GTSAM: SimpleRotation: a super-simple example of optimizing a single rotation according to a single prior @@ -11,18 +11,20 @@ errorStateKalmanFilter: simple 1D example of a moving target measured by a accel 2D Pose SLAM ============ -Pose2SLAMExample_easy: A 2D Pose SLAM example using the predefined typedefs in gtsam/slam/pose2SLAM.h +LocalizationExample.cpp: modeling robot motion +LocalizationExample2.cpp: example with GPS like measurements +Pose2SLAMExample: A 2D Pose SLAM example using the predefined typedefs in gtsam/slam/pose2SLAM.h Pose2SLAMExample_advanced: same, but uses an Optimizer object -Pose2SLAMwSPCG_easy: solve a simple 3 by 3 grid of Pose2 SLAM problem by using easy SPCG interface -Pose2SLAMwSPCG_advanced: solve a simple 3 by 3 grid of Pose2 SLAM problem by using advanced SPCG interface +Pose2SLAMwSPCG: solve a simple 3 by 3 grid of Pose2 SLAM problem by using easy SPCG interface Planar SLAM with landmarks ========================== PlanarSLAMExample: simple robotics example using the pre-built planar SLAM domain -PlanarSLAMSelfContained_advanced: simple robotics example with all typedefs internal to this script. +PlanarSLAMExample_selfcontained: simple robotics example with all typedefs internal to this script. Visual SLAM =========== +CameraResectioning.cpp: An example of gtsam for solving the camera resectioning problem The directory vSLAMexample includes 2 simple examples using GTSAM: - vSFMexample using visualSLAM in for structure-from-motion (SFM), and - vISAMexample using visualSLAM and ISAM for incremental SLAM updates diff --git a/examples/VisualSLAMExampleData.h b/examples/VisualSLAMExampleData.h new file mode 100644 index 000000000..f0ee4d2b5 --- /dev/null +++ b/examples/VisualSLAMExampleData.h @@ -0,0 +1,91 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file VisualSLAMSimulatedData.cpp + * @brief Generate ground-truth simulated data for VisualSLAM examples (SFM and ISAM2) + * @author Duy-Nguyen Ta + */ + +#pragma once + +#include +#include +#include + +/* ************************************************************************* */ +/** + * Simulated data for the example: + * - 8 Landmarks: (10,10,10) (-10,10,10) (-10,-10,10) (10,-10,10) + * (10,10,-10) (-10,10,-10) (-10,-10,-10) (10,-10,-10) + * - n 90-deg-FoV cameras with the same calibration parameters: + * f = 50.0, Image: 100x100, center: 50.0, 50.0 + * and ground-truth poses on a circle around the landmarks looking at the world's origin: + * Rot3(-sin(theta), 0, -cos(theta), + * cos(theta), 0, -sin(theta), + * 0, -1, 0 ), + * Point3(r*cos(theta), r*sin(theta), 0.0) + * (theta += 2*pi/N) + * - Measurement noise: 1 pix sigma + */ +struct VisualSLAMExampleData { + gtsam::shared_ptrK sK; // camera calibration parameters + std::vector poses; // ground-truth camera poses + gtsam::Pose3 odometry; // ground-truth odometry between 2 consecutive poses (simulated data for iSAM) + std::vector landmarks; // ground-truth landmarks + std::map > z; // 2D measurements of landmarks in each camera frame + gtsam::SharedDiagonal noiseZ; // measurement noise (noiseModel::Isotropic::Sigma(2, 5.0f)); + gtsam::SharedDiagonal noiseX; // noise for camera poses + gtsam::SharedDiagonal noiseL; // noise for landmarks + + static const VisualSLAMExampleData generate() { + VisualSLAMExampleData data; + // Landmarks (ground truth) + data.landmarks.push_back(gtsam::Point3(10.0,10.0,10.0)); + data.landmarks.push_back(gtsam::Point3(-10.0,10.0,10.0)); + data.landmarks.push_back(gtsam::Point3(-10.0,-10.0,10.0)); + data.landmarks.push_back(gtsam::Point3(10.0,-10.0,10.0)); + data.landmarks.push_back(gtsam::Point3(10.0,10.0,-10.0)); + data.landmarks.push_back(gtsam::Point3(-10.0,10.0,-10.0)); + data.landmarks.push_back(gtsam::Point3(-10.0,-10.0,-10.0)); + data.landmarks.push_back(gtsam::Point3(10.0,-10.0,-10.0)); + + // Camera calibration parameters + data.sK = gtsam::shared_ptrK(new gtsam::Cal3_S2(50.0, 50.0, 0.0, 50.0, 50.0)); + + // n camera poses + int n = 8; + double theta = 0.0; + double r = 30.0; + for (int i=0; isample())); + } + } + data.noiseX = gtsam::sharedSigmas(gtsam::Vector_(6, 0.01, 0.01, 0.01, 0.1, 0.1, 0.1)); + data.noiseL = gtsam::sharedSigma(3, 0.1); + + return data; + } +}; diff --git a/examples/VisualSLAMforSFMExample.cpp b/examples/VisualSLAMforSFMExample.cpp new file mode 100644 index 000000000..17f457908 --- /dev/null +++ b/examples/VisualSLAMforSFMExample.cpp @@ -0,0 +1,64 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file VisualSLAMforSFMExample.cpp + * @brief A visualSLAM example for the structure-from-motion problem on a simulated dataset + * @author Duy-Nguyen Ta + */ + +#include +#include +#include +#include +#include "VisualSLAMExampleData.h" + +using namespace std; +using namespace gtsam; + +// Convenience for named keys +using symbol_shorthand::X; +using symbol_shorthand::L; + +/* ************************************************************************* */ +int main(int argc, char* argv[]) { + + VisualSLAMExampleData data = VisualSLAMExampleData::generate(); + + /* 1. Create graph *///using the 2D measurements (features) and the calibration data + visualSLAM::Graph graph; + + /* 2. Add factors to the graph */ + // 2a. Measurement factors + for (size_t i=0; isample())); + for (size_t j=0; jsample())); + initial.print("Intial Estimates: "); + + /* 4. Optimize the graph and print results */ + visualSLAM::Values result = GaussNewtonOptimizer(graph, initial).optimize(); +// visualSLAM::Values result = LevenbergMarquardtOptimizer(graph, initial).optimize(); + result.print("Final results: "); + + return 0; +} +/* ************************************************************************* */ + diff --git a/examples/VisualSLAMwISAM2Example.cpp b/examples/VisualSLAMwISAM2Example.cpp new file mode 100644 index 000000000..1ec43136f --- /dev/null +++ b/examples/VisualSLAMwISAM2Example.cpp @@ -0,0 +1,113 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file VisualSLAMwISAM2Example.cpp + * @brief An ISAM example for synthesis sequence, single camera + * @author Duy-Nguyen Ta + */ + +#include +#include +#include +#include +#include "VisualSLAMExampleData.h" + +using namespace std; +using namespace gtsam; + +// Convenience for named keys +using symbol_shorthand::X; +using symbol_shorthand::L; + +/* ************************************************************************* */ +int main(int argc, char* argv[]) { + + VisualSLAMExampleData data = VisualSLAMExampleData::generate(); + + /* 1. Create a NonlinearISAM which will be relinearized and reordered after every "relinearizeInterval" updates */ + int relinearizeInterval = 3; + NonlinearISAM<> isam(relinearizeInterval); + + /* 2. At each frame (poseId) with new camera pose and set of associated measurements, + * create a graph of new factors and update ISAM */ + + // Store the current best estimate from ISAM + Values currentEstimate; + + // First two frames: + // Add factors and initial values for the first two poses and landmarks then update ISAM. + // Note: measurements from the first pose only are not enough to update ISAM: + // the system is underconstrained. + { + visualSLAM::Graph newFactors; + + // First pose with prior factor + newFactors.addPosePrior(X(0), data.poses[0], data.noiseX); + + // Second pose with odometry measurement, simulated by adding Gaussian noise to the ground-truth. + Pose3 odoMeasurement = data.odometry*Pose3::Expmap(data.noiseX->sample()); + newFactors.push_back( boost::shared_ptr >( + new BetweenFactor(X(0), X(1), odoMeasurement, data.noiseX))); + + // Visual measurements at both poses + for (size_t i=0; i<2; ++i) { + for (size_t j=0; jsample()); + initials.insert(X(0), pose0Init); + initials.insert(X(1), pose0Init*odoMeasurement); + + // Initial values for the landmarks, simulated with Gaussian noise + for (size_t j=0; jsample())); + + // Update ISAM the first time and obtain the current estimate + isam.update(newFactors, initials); + currentEstimate = isam.estimate(); + cout << "Frame 0 and 1: " << endl; + currentEstimate.print("Current estimate: "); + } + + // Subsequent frames: Add new odometry and measurement factors and initial values, + // then update ISAM at each frame + for (size_t i=2; isample()); + newFactors.push_back( boost::shared_ptr >( + new BetweenFactor(X(i-1), X(i), odoMeasurement, data.noiseX))); + // Factors for visual measurements + for (size_t j=0; j(X(i-1))*odoMeasurement); + + // update ISAM + isam.update(newFactors, initials); + currentEstimate = isam.estimate(); + cout << "****************************************************" << endl; + cout << "Frame " << i << ": " << endl; + currentEstimate.print("Current estimate: "); + } + + return 0; +} +/* ************************************************************************* */ + diff --git a/examples/easyPoint2KalmanFilter.cpp b/examples/easyPoint2KalmanFilter.cpp index b13058a07..2b4d2476a 100644 --- a/examples/easyPoint2KalmanFilter.cpp +++ b/examples/easyPoint2KalmanFilter.cpp @@ -22,6 +22,7 @@ */ #include +#include #include #include #include diff --git a/examples/matlab/LocalizationExample.m b/examples/matlab/LocalizationExample.m index 521c768ec..ae66a131c 100644 --- a/examples/matlab/LocalizationExample.m +++ b/examples/matlab/LocalizationExample.m @@ -45,9 +45,9 @@ result.print(sprintf('\nFinal result:\n ')); %% Query the marginals marginals = graph.marginals(result); -x{1}=gtsamSymbol('x',1); P{1}=marginals.marginalCovariance(x{1}.key) -x{2}=gtsamSymbol('x',2); P{2}=marginals.marginalCovariance(x{2}.key) -x{3}=gtsamSymbol('x',3); P{3}=marginals.marginalCovariance(x{3}.key) +P{1}=marginals.marginalCovariance(1); +P{2}=marginals.marginalCovariance(2); +P{3}=marginals.marginalCovariance(3); %% Plot Trajectory figure(1) diff --git a/examples/matlab/PlanarSLAMExample_easy.m b/examples/matlab/PlanarSLAMExample.m similarity index 80% rename from examples/matlab/PlanarSLAMExample_easy.m rename to examples/matlab/PlanarSLAMExample.m index 54462732b..88a988755 100644 --- a/examples/matlab/PlanarSLAMExample_easy.m +++ b/examples/matlab/PlanarSLAMExample.m @@ -20,24 +20,24 @@ % - Landmarks are 2 meters away from the robot trajectory %% Create keys for variables -x1 = 1; x2 = 2; x3 = 3; -l1 = 1; l2 = 2; +x1 = symbol('x',1); x2 = symbol('x',2); x3 = symbol('x',3); +l1 = symbol('l',1); l2 = symbol('l',2); %% Create graph container and add factors to it graph = planarSLAMGraph; %% Add prior % gaussian for prior -prior_model = gtsamSharedNoiseModel_Sigmas([0.3; 0.3; 0.1]); -prior_measurement = gtsamPose2(0.0, 0.0, 0.0); % prior at origin -graph.addPrior(x1, prior_measurement, prior_model); % add directly to graph +priorNoise = gtsamSharedNoiseModel_Sigmas([0.3; 0.3; 0.1]); +priorMean = gtsamPose2(0.0, 0.0, 0.0); % prior at origin +graph.addPrior(x1, priorMean, priorNoise); % add directly to graph %% Add odometry % general noisemodel for odometry -odom_model = gtsamSharedNoiseModel_Sigmas([0.2; 0.2; 0.1]); -odom_measurement = gtsamPose2(2.0, 0.0, 0.0); % create a measurement for both factors (the same in this case) -graph.addOdometry(x1, x2, odom_measurement, odom_model); -graph.addOdometry(x2, x3, odom_measurement, odom_model); +odometryNoise = gtsamSharedNoiseModel_Sigmas([0.2; 0.2; 0.1]); +odometry = gtsamPose2(2.0, 0.0, 0.0); % create a measurement for both factors (the same in this case) +graph.addOdometry(x1, x2, odometry, odometryNoise); +graph.addOdometry(x2, x3, odometry, odometryNoise); %% Add measurements % general noisemodel for measurements diff --git a/examples/matlab/Pose2SLAMExample_easy.m b/examples/matlab/Pose2SLAMExample.m similarity index 50% rename from examples/matlab/Pose2SLAMExample_easy.m rename to examples/matlab/Pose2SLAMExample.m index 6c359f314..5641d2ac3 100644 --- a/examples/matlab/Pose2SLAMExample_easy.m +++ b/examples/matlab/Pose2SLAMExample.m @@ -1,9 +1,9 @@ %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% -% GTSAM Copyright 2010, Georgia Tech Research Corporation, +% GTSAM Copyright 2010, Georgia Tech Research Corporation, % Atlanta, Georgia 30332-0415 % All Rights Reserved % Authors: Frank Dellaert, et al. (see THANKS for the full author list) -% +% % See LICENSE for the license information % % @brief Simple robotics example using the pre-built planar SLAM domain @@ -18,40 +18,39 @@ % - We have full odometry for measurements % - The robot is on a grid, moving 2 meters each step -%% Create keys for variables -x1 = 1; x2 = 2; x3 = 3; - %% Create graph container and add factors to it graph = pose2SLAMGraph; %% Add prior % gaussian for prior -prior_model = gtsamSharedNoiseModel_Sigmas([0.3; 0.3; 0.1]); -prior_measurement = gtsamPose2(0.0, 0.0, 0.0); % prior at origin -graph.addPrior(x1, prior_measurement, prior_model); % add directly to graph +priorMean = gtsamPose2(0.0, 0.0, 0.0); % prior at origin +priorNoise = gtsamSharedNoiseModel_Sigmas([0.3; 0.3; 0.1]); +graph.addPrior(1, priorMean, priorNoise); % add directly to graph %% Add odometry % general noisemodel for odometry -odom_model = gtsamSharedNoiseModel_Sigmas([0.2; 0.2; 0.1]); -odom_measurement = gtsamPose2(2.0, 0.0, 0.0); % create a measurement for both factors (the same in this case) -graph.addOdometry(x1, x2, odom_measurement, odom_model); -graph.addOdometry(x2, x3, odom_measurement, odom_model); +odometryNoise = gtsamSharedNoiseModel_Sigmas([0.2; 0.2; 0.1]); +graph.addOdometry(1, 2, gtsamPose2(2.0, 0.0, 0.0 ), odometryNoise); +graph.addOdometry(2, 3, gtsamPose2(2.0, 0.0, pi/2), odometryNoise); +graph.addOdometry(3, 4, gtsamPose2(2.0, 0.0, pi/2), odometryNoise); +graph.addOdometry(4, 5, gtsamPose2(2.0, 0.0, pi/2), odometryNoise); -%% Add measurements -% general noisemodel for measurements -meas_model = gtsamSharedNoiseModel_Sigmas([0.1; 0.2]); +%% Add pose constraint +model = gtsamSharedNoiseModel_Sigmas([0.2; 0.2; 0.1]); +graph.addConstraint(5, 2, gtsamPose2(2.0, 0.0, pi/2), model); % print -graph.print('full graph'); +graph.print(sprintf('\nFactor graph:\n')); %% Initialize to noisy points initialEstimate = pose2SLAMValues; -initialEstimate.insertPose(x1, gtsamPose2(0.5, 0.0, 0.2)); -initialEstimate.insertPose(x2, gtsamPose2(2.3, 0.1,-0.2)); -initialEstimate.insertPose(x3, gtsamPose2(4.1, 0.1, 0.1)); - -initialEstimate.print('initial estimate'); +initialEstimate.insertPose(1, gtsamPose2(0.5, 0.0, 0.2 )); +initialEstimate.insertPose(2, gtsamPose2(2.3, 0.1,-0.2 )); +initialEstimate.insertPose(3, gtsamPose2(4.1, 0.1, pi/2)); +initialEstimate.insertPose(4, gtsamPose2(4.0, 2.0, pi )); +initialEstimate.insertPose(5, gtsamPose2(2.1, 2.1,-pi/2)); +initialEstimate.print(sprintf('\nInitial estimate:\n')); %% Optimize using Levenberg-Marquardt optimization with an ordering from colamd result = graph.optimize(initialEstimate); -result.print('final result'); +result.print(sprintf('\nFinal result:\n')); diff --git a/examples/matlab/Pose2SLAMExample_advanced.m b/examples/matlab/Pose2SLAMExample_advanced.m index 2199def5b..f2739803e 100644 --- a/examples/matlab/Pose2SLAMExample_advanced.m +++ b/examples/matlab/Pose2SLAMExample_advanced.m @@ -20,24 +20,21 @@ % - We have full odometry for measurements % - The robot is on a grid, moving 2 meters each step -%% Create keys for variables -x1 = 1; x2 = 2; x3 = 3; - %% Create graph container and add factors to it graph = pose2SLAMGraph; %% Add prior % gaussian for prior -prior_model = gtsamSharedNoiseModel_Sigmas([0.3; 0.3; 0.1]); -prior_measurement = gtsamPose2(0.0, 0.0, 0.0); % prior at origin -graph.addPrior(x1, prior_measurement, prior_model); % add directly to graph +priorNoise = gtsamSharedNoiseModel_Sigmas([0.3; 0.3; 0.1]); +priorMean = gtsamPose2(0.0, 0.0, 0.0); % prior at origin +graph.addPrior(1, priorMean, priorNoise); % add directly to graph %% Add odometry % general noisemodel for odometry -odom_model = gtsamSharedNoiseModel_Sigmas([0.2; 0.2; 0.1]); -odom_measurement = gtsamPose2(2.0, 0.0, 0.0); % create a measurement for both factors (the same in this case) -graph.addOdometry(x1, x2, odom_measurement, odom_model); -graph.addOdometry(x2, x3, odom_measurement, odom_model); +odometryNoise = gtsamSharedNoiseModel_Sigmas([0.2; 0.2; 0.1]); +odometry = gtsamPose2(2.0, 0.0, 0.0); % create a measurement for both factors (the same in this case) +graph.addOdometry(1, 2, odometry, odometryNoise); +graph.addOdometry(2, 3, odometry, odometryNoise); %% Add measurements % general noisemodel for measurements @@ -48,9 +45,9 @@ graph.print('full graph'); %% Initialize to noisy points initialEstimate = pose2SLAMValues; -initialEstimate.insertPose(x1, gtsamPose2(0.5, 0.0, 0.2)); -initialEstimate.insertPose(x2, gtsamPose2(2.3, 0.1,-0.2)); -initialEstimate.insertPose(x3, gtsamPose2(4.1, 0.1, 0.1)); +initialEstimate.insertPose(1, gtsamPose2(0.5, 0.0, 0.2)); +initialEstimate.insertPose(2, gtsamPose2(2.3, 0.1,-0.2)); +initialEstimate.insertPose(3, gtsamPose2(4.1, 0.1, 0.1)); initialEstimate.print('initial estimate'); @@ -62,10 +59,7 @@ initialEstimate.print('initial estimate'); %result = pose2SLAMOptimizer(graph,initialEstimate,ord,params); %result.print('final result'); -% % -% % disp('\\\'); -% % -% % %% Optimize using Levenberg-Marquardt optimization with an ordering from colamd +%% Optimize using Levenberg-Marquardt optimization with an ordering from colamd result = graph.optimize(initialEstimate); result.print('final result'); diff --git a/examples/matlab/Pose2SLAMExample_circle.m b/examples/matlab/Pose2SLAMExample_circle.m new file mode 100644 index 000000000..7e7ab6694 --- /dev/null +++ b/examples/matlab/Pose2SLAMExample_circle.m @@ -0,0 +1,48 @@ +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% +% GTSAM Copyright 2010, Georgia Tech Research Corporation, +% Atlanta, Georgia 30332-0415 +% All Rights Reserved +% Authors: Frank Dellaert, et al. (see THANKS for the full author list) +% +% See LICENSE for the license information +% +% @brief Read graph from file and perform GraphSLAM +% @author Frank Dellaert +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% + +%% Create a hexagon of poses +hexagon = pose2SLAMValues_Circle(6,1.0); +p0 = hexagon.pose(0); +p1 = hexagon.pose(1); + +%% create a Pose graph with one equality constraint and one measurement +fg = pose2SLAMGraph; +fg.addPoseConstraint(0, p0); +delta = p0.between(p1); +covariance = gtsamSharedNoiseModel_Sigmas([0.05; 0.05; 5*pi/180]); +fg.addOdometry(0,1, delta, covariance); +fg.addOdometry(1,2, delta, covariance); +fg.addOdometry(2,3, delta, covariance); +fg.addOdometry(3,4, delta, covariance); +fg.addOdometry(4,5, delta, covariance); +fg.addOdometry(5,0, delta, covariance); + +%% Create initial config +initial = pose2SLAMValues; +initial.insertPose(0, p0); +initial.insertPose(1, hexagon.pose(1).retract([-0.1, 0.1,-0.1]')); +initial.insertPose(2, hexagon.pose(2).retract([ 0.1,-0.1, 0.1]')); +initial.insertPose(3, hexagon.pose(3).retract([-0.1, 0.1,-0.1]')); +initial.insertPose(4, hexagon.pose(4).retract([ 0.1,-0.1, 0.1]')); +initial.insertPose(5, hexagon.pose(5).retract([-0.1, 0.1,-0.1]')); + +%% Plot Initial Estimate +figure(1);clf +plot(initial.xs(),initial.ys(),'g-*'); axis equal + +%% optimize +result = fg.optimize(initial); + +%% Show Result +hold on; plot(result.xs(),result.ys(),'b-*') +result.print(sprintf('\nFinal result:\n')); diff --git a/examples/matlab/Pose2SLAMExample_graph.m b/examples/matlab/Pose2SLAMExample_graph.m new file mode 100644 index 000000000..142c9b36d --- /dev/null +++ b/examples/matlab/Pose2SLAMExample_graph.m @@ -0,0 +1,39 @@ +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% +% GTSAM Copyright 2010, Georgia Tech Research Corporation, +% Atlanta, Georgia 30332-0415 +% All Rights Reserved +% Authors: Frank Dellaert, et al. (see THANKS for the full author list) +% +% See LICENSE for the license information +% +% @brief Read graph from file and perform GraphSLAM +% @author Frank Dellaert +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% + +%% Initialize graph, initial estimate, and odometry noise +model = gtsamSharedNoiseModel_Sigmas([0.05; 0.05; 5*pi/180]); +[graph,initial]=load2D('../Data/w100-odom.graph',model); +initial.print(sprintf('Initial estimate:\n')); + +%% Add a Gaussian prior on pose x_1 +priorMean = gtsamPose2(0.0, 0.0, 0.0); % prior mean is at origin +priorNoise = gtsamSharedNoiseModel_Sigmas([0.01; 0.01; 0.01]); +graph.addPrior(0, priorMean, priorNoise); % add directly to graph + +%% Plot Initial Estimate +figure(1);clf +plot(initial.xs(),initial.ys(),'g-*'); axis equal + +%% Optimize using Levenberg-Marquardt optimization with an ordering from colamd +result = graph.optimize(initial); +hold on; plot(result.xs(),result.ys(),'b-*') +result.print(sprintf('\nFinal result:\n')); + +%% Plot Covariance Ellipses +marginals = graph.marginals(result); +for i=1:result.size()-1 + pose_i = result.pose(i); + P{i}=marginals.marginalCovariance(i); + covarianceEllipse([pose_i.x;pose_i.y],P{i},'b') +end +fprintf(1,'%.5f %.5f %.5f\n',P{99}) \ No newline at end of file diff --git a/examples/matlab/Pose3SLAMExample_circle.m b/examples/matlab/Pose3SLAMExample_circle.m new file mode 100644 index 000000000..d1676626c --- /dev/null +++ b/examples/matlab/Pose3SLAMExample_circle.m @@ -0,0 +1,49 @@ +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% +% GTSAM Copyright 2010, Georgia Tech Research Corporation, +% Atlanta, Georgia 30332-0415 +% All Rights Reserved +% Authors: Frank Dellaert, et al. (see THANKS for the full author list) +% +% See LICENSE for the license information +% +% @brief Read graph from file and perform GraphSLAM +% @author Frank Dellaert +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% + +%% Create a hexagon of poses +hexagon = pose3SLAMValues_Circle(6,1.0); +p0 = hexagon.pose(0); +p1 = hexagon.pose(1); + +%% create a Pose graph with one equality constraint and one measurement +fg = pose3SLAMGraph; +fg.addHardConstraint(0, p0); +delta = p0.between(p1); +covariance = gtsamSharedNoiseModel_Sigmas([0.05; 0.05; 0.05; 5*pi/180; 5*pi/180; 5*pi/180]); +fg.addConstraint(0,1, delta, covariance); +fg.addConstraint(1,2, delta, covariance); +fg.addConstraint(2,3, delta, covariance); +fg.addConstraint(3,4, delta, covariance); +fg.addConstraint(4,5, delta, covariance); +fg.addConstraint(5,0, delta, covariance); + +%% Create initial config +initial = pose3SLAMValues; +s = 0.10; +initial.insertPose(0, p0); +initial.insertPose(1, hexagon.pose(1).retract(s*randn(6,1))); +initial.insertPose(2, hexagon.pose(2).retract(s*randn(6,1))); +initial.insertPose(3, hexagon.pose(3).retract(s*randn(6,1))); +initial.insertPose(4, hexagon.pose(4).retract(s*randn(6,1))); +initial.insertPose(5, hexagon.pose(5).retract(s*randn(6,1))); + +%% Plot Initial Estimate +figure(1);clf +plot3(initial.xs(),initial.ys(),initial.zs(),'g-*'); axis equal + +%% optimize +result = fg.optimize(initial); + +%% Show Result +hold on; plot3(result.xs(),result.ys(),result.zs(),'b-*') +result.print(sprintf('\nFinal result:\n')); diff --git a/examples/matlab/Pose3SLAMExample_graph.m b/examples/matlab/Pose3SLAMExample_graph.m new file mode 100644 index 000000000..b1f0afb1a --- /dev/null +++ b/examples/matlab/Pose3SLAMExample_graph.m @@ -0,0 +1,33 @@ +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% +% GTSAM Copyright 2010, Georgia Tech Research Corporation, +% Atlanta, Georgia 30332-0415 +% All Rights Reserved +% Authors: Frank Dellaert, et al. (see THANKS for the full author list) +% +% See LICENSE for the license information +% +% @brief Read graph from file and perform GraphSLAM +% @author Frank Dellaert +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% + +N = 2500; +% filename = '../Data/sphere_smallnoise.graph'; +% filename = '../Data/sphere2500_groundtruth.txt'; +filename = '../Data/sphere2500.txt'; + +%% Initialize graph, initial estimate, and odometry noise +model = gtsamSharedNoiseModel_Sigmas([0.05; 0.05; 0.05; 5*pi/180; 5*pi/180; 5*pi/180]); +[graph,initial]=load3D(filename,model,true,N); +first = initial.pose(0); +graph.addHardConstraint(0, first); + +%% Plot Initial Estimate +figure(1);clf +plot3(first.x(),first.y(),first.z(),'r*'); hold on +plot3DTrajectory(initial,'g-',false); + +%% Read again, now all constraints +[graph,discard]=load3D(filename,model,false,N); +graph.addHardConstraint(0, first); +result = graph.optimize(initial); % start from old result +plot3DTrajectory(result,'r-',false); axis equal; diff --git a/examples/matlab/load2D.m b/examples/matlab/load2D.m new file mode 100644 index 000000000..e459dfc63 --- /dev/null +++ b/examples/matlab/load2D.m @@ -0,0 +1,29 @@ +function [graph,initial] = load2D(filename,model) +% load2D: read TORO pose graph +% cannot read noise model from file yet, uses specified model + +fid = fopen(filename); +if fid < 0 + error(['load2D: Cannot open file ' filename]); +end + +% scan all lines into a cell array +columns=textscan(fid,'%s','delimiter','\n'); +fclose(fid); +lines=columns{1}; + +% loop over lines and add vertices +graph = pose2SLAMGraph; +initial = pose2SLAMValues; +n=size(lines,1); +for i=1:n + line_i=lines{i}; + if strcmp('VERTEX2',line_i(1:7)) + v = textscan(line_i,'%s %d %f %f %f',1); + initial.insertPose(v{2}, gtsamPose2(v{3}, v{4}, v{5})); + elseif strcmp('EDGE2',line_i(1:5)) + e = textscan(line_i,'%s %d %d %f %f %f',1); + graph.addOdometry(e{2}, e{3}, gtsamPose2(e{4}, e{5}, e{6}), model); + end +end + diff --git a/examples/matlab/load3D.m b/examples/matlab/load3D.m new file mode 100644 index 000000000..82ae098b9 --- /dev/null +++ b/examples/matlab/load3D.m @@ -0,0 +1,56 @@ +function [graph,initial] = load3D(filename,model,successive,N) +% load3D: read TORO 3D pose graph +% cannot read noise model from file yet, uses specified model +% if [successive] is tru, constructs initial estimate from odometry + +if nargin<3, successive=false; end +fid = fopen(filename); +if fid < 0 + error(['load2D: Cannot open file ' filename]); +end + +% scan all lines into a cell array +columns=textscan(fid,'%s','delimiter','\n'); +fclose(fid); +lines=columns{1}; + +% loop over lines and add vertices +graph = pose3SLAMGraph; +initial = pose3SLAMValues; +origin=gtsamPose3; +initial.insertPose(0,origin); +n=size(lines,1); +if nargin<4, N=n;end + +for i=1:n + line_i=lines{i}; + if strcmp('VERTEX3',line_i(1:7)) + v = textscan(line_i,'%s %d %f %f %f %f %f %f',1); + i=v{2}; + if (~successive & ii1 + initial.insertPose(i2,initial.pose(i1).compose(dpose)); + else + initial.insertPose(i1,initial.pose(i2).compose(dpose.inverse)); + end + end + end + end + end +end + diff --git a/examples/matlab/plot3DTrajectory.m b/examples/matlab/plot3DTrajectory.m new file mode 100644 index 000000000..f2c1d8f2f --- /dev/null +++ b/examples/matlab/plot3DTrajectory.m @@ -0,0 +1,15 @@ +function plot3DTrajectory(values,style,frames) +% plot3DTrajectory +if nargin<3,frames=false;end + +plot3(values.xs(),values.ys(),values.zs(),style); hold on +if frames + for i=0:N-1 + pose = values.pose(i); + t = pose.translation; + R = pose.rotation.matrix; + quiver3(t.x,t.y,t.z,R(1,1),R(2,1),R(3,1),'r'); + quiver3(t.x,t.y,t.z,R(1,2),R(2,2),R(3,2),'g'); + quiver3(t.x,t.y,t.z,R(1,3),R(2,3),R(3,3),'b'); + end +end \ No newline at end of file diff --git a/examples/matlab/symbol.m b/examples/matlab/symbol.m new file mode 100644 index 000000000..c7c4af2c6 --- /dev/null +++ b/examples/matlab/symbol.m @@ -0,0 +1,4 @@ +function key = symbol(c,i) +% generate a key corresponding to a symbol +s = gtsamSymbol(c,i); +key = s.key(); \ No newline at end of file diff --git a/examples/vSLAMexample/CMakeLists.txt b/examples/vSLAMexample/CMakeLists.txt deleted file mode 100644 index e231a03e6..000000000 --- a/examples/vSLAMexample/CMakeLists.txt +++ /dev/null @@ -1,22 +0,0 @@ -# Build vSLAMexample - -message(STATUS "Adding Example vISAMexample") -add_executable(vISAMexample vISAMexample.cpp vSLAMutils.cpp) -target_link_libraries(vISAMexample gtsam-static) -if(NOT MSVC) - add_dependencies(examples vISAMexample) -else() - set_property(TARGET vISAMexample PROPERTY FOLDER "Examples") -endif() - -message(STATUS "Adding Example vSFMexample") -add_executable(vSFMexample vSFMexample.cpp vSLAMutils.cpp) -target_link_libraries(vSFMexample gtsam-static) -if(NOT MSVC) - add_dependencies(examples vSFMexample) -else() - set_property(TARGET vSFMexample PROPERTY FOLDER "Examples") -endif() - - - diff --git a/examples/vSLAMexample/Feature2D.h b/examples/vSLAMexample/Feature2D.h deleted file mode 100644 index aca5f9e4b..000000000 --- a/examples/vSLAMexample/Feature2D.h +++ /dev/null @@ -1,41 +0,0 @@ -/* ---------------------------------------------------------------------------- - - * GTSAM Copyright 2010, Georgia Tech Research Corporation, - * Atlanta, Georgia 30332-0415 - * All Rights Reserved - * Authors: Frank Dellaert, et al. (see THANKS for the full author list) - - * See LICENSE for the license information - - * -------------------------------------------------------------------------- */ - -/** - * @file Feature2D.h - * @brief - * @author Duy-Nguyen Ta - */ - -#pragma once - -#include "gtsam/geometry/Point2.h" -#include - -struct Feature2D -{ - - gtsam::Point2 m_p; - int m_idCamera; // id of the camera pose that makes this measurement - int m_idLandmark; // id of the 3D landmark that it is associated with - - Feature2D(int idCamera, int idLandmark, gtsam::Point2 p) : - m_p(p), - m_idCamera(idCamera), - m_idLandmark(idLandmark) {} - - void print(const std::string& s = "") const { - std::cout << s << std::endl; - std::cout << "Pose id: " << m_idCamera << " -- Landmark id: " << m_idLandmark << std::endl; - m_p.print("\tMeasurement: "); - } - -}; diff --git a/examples/vSLAMexample/README b/examples/vSLAMexample/README deleted file mode 100644 index 99b10608c..000000000 --- a/examples/vSLAMexample/README +++ /dev/null @@ -1,101 +0,0 @@ -README - vSLAMexample ------------------------------------------------------- - - vSLAMexample includes 2 simple examples using GTSAM: - - vSFMexample using visualSLAM in for structure-from-motion (SFM), and - - vISAMexample using visualSLAM and ISAM for incremental SLAM updates - - The two examples use the same visual SLAM graph structure which nodes are 6d camera poses (SE3) and 3d point landmarks. Measurement factors are 2D features detected on each image, connecting its camera-pose node and the corresponding landmark nodes. There are also prior factors on each pose nodes. - -Synthesized data generation ---------------------------- -The data are generated by using Panda3D graphics engine to render a sequence of virtual scene with 7 colorful small 3d patches viewing by camera moving around. The patches' coordinates are given in "landmarks.txt" file. Centroids of those colorful features in the rendered images are detected and stored in "ttpy*.feat" files. - -Files "ttpy*.pose" contain the poses of the virtual camera that renders the scene. A *VERY IMPORTANT* note is that the values in these "ttpy*.pose" files follow Panda3D's convention for camera frame coordinate system: "z up, y view", where as in our code, we follow OpenGL's convention: "y up, -z view". Thus, we have to change it to match with our convention. Essentially, the z- and y- axes are swapped, then the z-axis is negated to stick to the right-hand rule. Please see the function "gtsam::Pose3 readPose(const char* Fn)" in "vSLAMutils.cpp" for more information. - -File "calib.txt" contains intrinsic parameters of the virtual camera. The signs are correctly adjusted to match with our projection coordinate system's convention. - -Files "measurements.txt" and "poses.txt" simulate typical input data for a structure-from-motion problem. Similarly, "measurementsISAM.txt" and "posesISAM.txt" simulate the data used in SLAM context with incremental-update using ISAM. - -Note that for SFM, the whole graph is solved as a whole batch problem, so the camera_id's corresponding to the feature files and pose files need to be specified in "measurements.txt" and "poses.txt", but they are not necessarily in order. - -On the other hand, for ISAM, we sequentially add the camera poses and features and update after every frame; so the pose files and features files in "measurementsISAM.txt" and "posesISAM.txt" need to be specified in order (time order), even though the camera id's are not necessary. - - - -Data file format ------------------------------ - -"calib.txt": ------------- -image_width image_height fx fy ox oy - - -"landmarks.txt" ------------- -N #number of landmarks -landmark_id1 x1 y1 z1 -landmark_id2 x2 y2 z2 -... -landmark_idN xN yN zN - - -"ttpy*.feat" ------------- -N #number of features -corresponding_landmark_id1 x1 y1 -corresponding_landmark_id2 x2 y2 -... -corresponding_landmark_idN xN yN - - -"ttpy*.pose" ------------- -0.939693 0.34202 0 0 --0.241845 0.664463 -0.707107 0 --0.241845 0.664463 0.707107 0 -34.202 -93.9693 100 1 - -The camera pose matrix in column order. Note that these values follows Panda3D's convention for camera coordinate frame. We have to change it to match with our convention used in the code, which follows OpenGL system. See previous section for more details. - - -Data For SFM: - -"measurements.txt" ------------- -N #number of cameras -camera_id1 featureFile1 -camera_id2 featureFile2 -... -camera_id3 featureFile3 - -"poses.txt" ------------- -N #number of cameras -camera_id1 poseFile1 -camera_id2 poseFile2 -... -camera_id3 poseFile3 - - -Data For ISAM: - -"measurementsISAM.txt" ------------- -N #number of cameras -featureFile1 -featureFile2 -... -featureFile3 - -"posesISAM.txt" ------------- -N #number of cameras -poseFile1 -poseFile2 -... -poseFile3 - - - - diff --git a/examples/vSLAMexample/vISAMexample.cpp b/examples/vSLAMexample/vISAMexample.cpp deleted file mode 100644 index 7c16072d8..000000000 --- a/examples/vSLAMexample/vISAMexample.cpp +++ /dev/null @@ -1,144 +0,0 @@ -/* ---------------------------------------------------------------------------- - - * GTSAM Copyright 2010, Georgia Tech Research Corporation, - * Atlanta, Georgia 30332-0415 - * All Rights Reserved - * Authors: Frank Dellaert, et al. (see THANKS for the full author list) - - * See LICENSE for the license information - - * -------------------------------------------------------------------------- */ - -/** - * @file vISAMexample.cpp - * @brief An ISAM example for synthesis sequence - * single camera - * @author Duy-Nguyen Ta - */ - -#include -#include -using namespace boost; - -#include -#include -#include -#include -#include - -#include "vSLAMutils.h" -#include "Feature2D.h" - -using namespace std; -using namespace gtsam; -using namespace visualSLAM; -using namespace boost; - -/* ************************************************************************* */ -#define CALIB_FILE "calib.txt" -#define LANDMARKS_FILE "landmarks.txt" -#define POSES_FILE "poses.txt" -#define MEASUREMENTS_FILE "measurements.txt" - -// Base data folder -string g_dataFolder; - -// Store groundtruth values, read from files -shared_ptrK g_calib; -map g_landmarks; // map: -map g_poses; // map: -std::map > g_measurements; // feature sets detected at each frame - -// Noise models -SharedNoiseModel measurementSigma(noiseModel::Isotropic::Sigma(2, 5.0f)); -SharedNoiseModel poseSigma(noiseModel::Unit::Create(1)); - - -/* ************************************************************************* */ -/** - * Read all data: calibration file, landmarks, poses, and all features measurements - * Data is stored in global variables, which are used later to simulate incremental updates. - */ -void readAllDataISAM() { - g_calib = readCalibData(g_dataFolder + CALIB_FILE); - - // Read groundtruth landmarks' positions. These will be used later as intial estimates and priors for landmark nodes. - g_landmarks = readLandMarks(g_dataFolder + LANDMARKS_FILE); - - // Read groundtruth camera poses. These will be used later as intial estimates for pose nodes. - g_poses = readPoses(g_dataFolder, POSES_FILE); - - // Read all 2d measurements. Those will become factors linking their associating pose and the corresponding landmark. - g_measurements = readAllMeasurementsISAM(g_dataFolder, MEASUREMENTS_FILE); -} - -/* ************************************************************************* */ -/** - * Setup newFactors and initialValues for each new pose and set of measurements at each frame. - */ -void createNewFactors(boost::shared_ptr& newFactors, boost::shared_ptr& initialValues, - int pose_id, const Pose3& pose, const std::vector& measurements, SharedNoiseModel measurementSigma, shared_ptrK calib) { - - // Create a graph of newFactors with new measurements - newFactors = boost::shared_ptr (new Graph()); - for (size_t i = 0; i < measurements.size(); i++) { - newFactors->addMeasurement( - measurements[i].m_p, - measurementSigma, - pose_id, - measurements[i].m_idLandmark, - calib); - } - - // ... we need priors on the new pose and all new landmarks - newFactors->addPosePrior(pose_id, pose, poseSigma); - for (size_t i = 0; i < measurements.size(); i++) { - newFactors->addPointPrior(measurements[i].m_idLandmark, g_landmarks[measurements[i].m_idLandmark]); - } - - // Create initial values for all nodes in the newFactors - initialValues = boost::shared_ptr (new Values()); - initialValues->insert(PoseKey(pose_id), pose); - for (size_t i = 0; i < measurements.size(); i++) { - initialValues->insert(PointKey(measurements[i].m_idLandmark), g_landmarks[measurements[i].m_idLandmark]); - } -} - -/* ************************************************************************* */ -int main(int argc, char* argv[]) { - if (argc < 2) { - cout << "Usage: vISAMexample " << endl << endl; - cout << "\tPlease specify , which contains calibration file, initial\n" - "\tlandmarks, initial poses, and feature data." << endl; - cout << "\tSample folder is in $gtsam_source_folder$/examples/Data/" << endl << endl; - cout << "Example usage: vISAMexample '$gtsam_source_folder$/examples/Data/'" << endl; - exit(0); - } - - g_dataFolder = string(argv[1]) + "/"; - readAllDataISAM(); - - // Create a NonlinearISAM which will be relinearized and reordered after every "relinearizeInterval" updates - int relinearizeInterval = 3; - NonlinearISAM<> isam(relinearizeInterval); - - // At each frame (poseId) with new camera pose and set of associated measurements, - // create a graph of new factors and update ISAM - typedef std::map > FeatureMap; - BOOST_FOREACH(const FeatureMap::value_type& features, g_measurements) { - const int poseId = features.first; - boost::shared_ptr newFactors; - boost::shared_ptr initialValues; - createNewFactors(newFactors, initialValues, poseId, g_poses[poseId], - features.second, measurementSigma, g_calib); - - isam.update(*newFactors, *initialValues); - Values currentEstimate = isam.estimate(); - cout << "****************************************************" << endl; - currentEstimate.print("Current estimate: "); - } - - return 1; -} -/* ************************************************************************* */ - diff --git a/examples/vSLAMexample/vSFMexample.cpp b/examples/vSLAMexample/vSFMexample.cpp deleted file mode 100644 index 8774b79f3..000000000 --- a/examples/vSLAMexample/vSFMexample.cpp +++ /dev/null @@ -1,157 +0,0 @@ -/* ---------------------------------------------------------------------------- - - * GTSAM Copyright 2010, Georgia Tech Research Corporation, - * Atlanta, Georgia 30332-0415 - * All Rights Reserved - * Authors: Frank Dellaert, et al. (see THANKS for the full author list) - - * See LICENSE for the license information - - * -------------------------------------------------------------------------- */ - -/** - * @file vSFMexample.cpp - * @brief An vSFM example for synthesis sequence - * single camera - * @author Duy-Nguyen Ta - */ - -#include -using namespace boost; - -#include -#include -#include -#include - -#include "vSLAMutils.h" -#include "Feature2D.h" - -using namespace std; -using namespace gtsam; -using namespace visualSLAM; -using namespace boost; - -/* ************************************************************************* */ -#define CALIB_FILE "calib.txt" -#define LANDMARKS_FILE "landmarks.txt" -#define POSES_FILE "poses.txt" -#define MEASUREMENTS_FILE "measurements.txt" - -// Base data folder -string g_dataFolder; - -// Store groundtruth values, read from files -shared_ptrK g_calib; -map g_landmarks; // map: -map g_poses; // map: -std::vector g_measurements; // Feature2D: {camera_id, landmark_id, 2d feature_position} - -// Noise models -SharedNoiseModel measurementSigma(noiseModel::Isotropic::Sigma(2, 5.0f)); - -/* ************************************************************************* */ -/** - * Read all data: calibration file, landmarks, poses, and all features measurements - * Data is stored in global variables. - */ -void readAllData() { - - g_calib = readCalibData(g_dataFolder + "/" + CALIB_FILE); - - // Read groundtruth landmarks' positions. These will be used later as intial estimates for landmark nodes. - g_landmarks = readLandMarks(g_dataFolder + "/" + LANDMARKS_FILE); - - // Read groundtruth camera poses. These will be used later as intial estimates for pose nodes. - g_poses = readPoses(g_dataFolder, POSES_FILE); - - // Read all 2d measurements. Those will become factors linking their associating pose and the corresponding landmark. - g_measurements = readAllMeasurements(g_dataFolder, MEASUREMENTS_FILE); -} - -/* ************************************************************************* */ -/** - * Setup vSLAM graph - * by adding and linking 2D features (measurements) detected in each captured image - * with their corresponding landmarks. - */ -Graph setupGraph(std::vector& measurements, SharedNoiseModel measurementSigma, shared_ptrK calib) { - - Graph g; - - cout << "Built graph: " << endl; - for (size_t i = 0; i < measurements.size(); i++) { - measurements[i].print(); - - g.addMeasurement( - measurements[i].m_p, - measurementSigma, - measurements[i].m_idCamera, - measurements[i].m_idLandmark, - calib); - } - - return g; -} - -/* ************************************************************************* */ -/** - * Create a structure of initial estimates for all nodes (landmarks and poses) in the graph. - * The returned Values structure contains all initial values for all nodes. - */ -Values initialize(std::map landmarks, std::map poses) { - - Values initValues; - - // Initialize landmarks 3D positions. - for (map::iterator lmit = landmarks.begin(); lmit != landmarks.end(); lmit++) - initValues.insert(PointKey(lmit->first), lmit->second); - - // Initialize camera poses. - for (map::iterator poseit = poses.begin(); poseit != poses.end(); poseit++) - initValues.insert(PoseKey(poseit->first), poseit->second); - - return initValues; -} - -/* ************************************************************************* */ -int main(int argc, char* argv[]) { - if (argc < 2) { - cout << "Usage: vSFMexample " << endl << endl; - cout << "\tPlease specify , which contains calibration file, initial\n" - "\tlandmarks, initial poses, and feature data." << endl; - cout << "\tSample folder is in $gtsam_source_folder$/examples/Data" << endl << endl; - cout << "Example usage: vSFMexample '$gtsam_source_folder$/examples/Data'" << endl; - exit(0); - } - - g_dataFolder = string(argv[1]) + "/"; - readAllData(); - - // Create a graph using the 2D measurements (features) and the calibration data - Graph graph(setupGraph(g_measurements, measurementSigma, g_calib)); - - // Create an initial Values structure using groundtruth values as the initial estimates - Values initialEstimates(initialize(g_landmarks, g_poses)); - cout << "*******************************************************" << endl; - initialEstimates.print("INITIAL ESTIMATES: "); - - // Add prior factor for all poses in the graph - map::iterator poseit = g_poses.begin(); - for (; poseit != g_poses.end(); poseit++) - graph.addPosePrior(poseit->first, poseit->second, noiseModel::Unit::Create(1)); - - // Optimize the graph - cout << "*******************************************************" << endl; - LevenbergMarquardtParams params; - params.verbosityLM = LevenbergMarquardtParams::DAMPED; - visualSLAM::Values result = LevenbergMarquardtOptimizer(graph, initialEstimates, params).optimize(); - - // Print final results - cout << "*******************************************************" << endl; - result.print("FINAL RESULTS: "); - - return 0; -} -/* ************************************************************************* */ - diff --git a/examples/vSLAMexample/vSLAMutils.cpp b/examples/vSLAMexample/vSLAMutils.cpp deleted file mode 100644 index 1c3912f2d..000000000 --- a/examples/vSLAMexample/vSLAMutils.cpp +++ /dev/null @@ -1,176 +0,0 @@ -/* ---------------------------------------------------------------------------- - - * GTSAM Copyright 2010, Georgia Tech Research Corporation, - * Atlanta, Georgia 30332-0415 - * All Rights Reserved - * Authors: Frank Dellaert, et al. (see THANKS for the full author list) - - * See LICENSE for the license information - - * -------------------------------------------------------------------------- */ - -/** - * @file VSLAMutils.cpp - * @brief - * @author Duy-Nguyen Ta - */ - -#include "vSLAMutils.h" -#include -#include - -using namespace gtsam; -using namespace std; - -/* ************************************************************************* */ -std::map readLandMarks(const std::string& landmarkFile) { - ifstream file(landmarkFile.c_str()); - if (!file) { - cout << "Cannot read landmark file: " << landmarkFile << endl; - exit(0); - } - - int num; - file >> num; - std::map landmarks; - landmarks.clear(); - for (int i = 0; i> color_id >> x >> y >> z; - landmarks[color_id] = Point3(x, y, z); - } - - file.close(); - return landmarks; -} - -/* ************************************************************************* */ -gtsam::Pose3 readPose(const char* Fn) { - ifstream poseFile(Fn); - if (!poseFile) { - cout << "Cannot read pose file: " << Fn << endl; - exit(0); - } - - double v[16]; - for (int i = 0; i<16; i++) - poseFile >> v[i]; - poseFile.close(); - - Matrix T = Matrix_(4,4, v); // row order !!! - - Pose3 pose(T); - return pose; -} -/* ************************************************************************* */ -std::map readPoses(const std::string& baseFolder, const std::string& posesFn) { - ifstream posesFile((baseFolder+posesFn).c_str()); - if (!posesFile) { - cout << "Cannot read all pose file: " << posesFn << endl; - exit(0); - } - int numPoses; - posesFile >> numPoses; - map poses; - for (int i = 0; i> poseId; - - string poseFileName; - posesFile >> poseFileName; - - Pose3 pose = readPose((baseFolder+poseFileName).c_str()); - poses[poseId] = pose; - } - - return poses; -} - -/* ************************************************************************* */ -gtsam::shared_ptrK readCalibData(const std::string& calibFn) { - ifstream calibFile(calibFn.c_str()); - if (!calibFile) { - cout << "Cannot read calib file: " << calibFn << endl; - exit(0); - } - int imX, imY; - float fx, fy, ox, oy; - calibFile >> imX >> imY >> fx >> fy >> ox >> oy; - calibFile.close(); - - return shared_ptrK(new Cal3_S2(fx, fy, 0, ox, oy)); // skew factor = 0 -} - -/* ************************************************************************* */ -std::vector readFeatures(int pose_id, const char* filename) { - ifstream file(filename); - if (!file) { - cout << "Cannot read feature file: " << filename<< endl; - exit(0); - } - - int numFeatures; - file >> numFeatures ; - - std::vector vFeatures_; - for (int i = 0; i < numFeatures; i++) { - int landmark_id; double x, y; - file >> landmark_id >> x >> y; - vFeatures_.push_back(Feature2D(pose_id, landmark_id, Point2(x, y))); - } - - file.close(); - return vFeatures_; -} - -/* ************************************************************************* */ -std::vector readAllMeasurements(const std::string& baseFolder, const std::string& measurementsFn) { - ifstream measurementsFile((baseFolder+measurementsFn).c_str()); - if (!measurementsFile) { - cout << "Cannot read all pose file: " << baseFolder+measurementsFn << endl; - exit(0); - } - int numPoses; - measurementsFile >> numPoses; - - vector allFeatures; - allFeatures.clear(); - - for (int i = 0; i> poseId; - - string featureFileName; - measurementsFile >> featureFileName; - vector features = readFeatures(poseId, (baseFolder+featureFileName).c_str()); - allFeatures.insert( allFeatures.end(), features.begin(), features.end() ); - } - - return allFeatures; -} - -/* ************************************************************************* */ -std::map > readAllMeasurementsISAM(const std::string& baseFolder, const std::string& measurementsFn) { - ifstream measurementsFile((baseFolder+measurementsFn).c_str()); - if (!measurementsFile) { - cout << "Cannot read all pose file: " << baseFolder+measurementsFn << endl; - exit(0); - } - int numPoses; - measurementsFile >> numPoses; - - std::map > allFeatures; - - for (int i = 0; i> poseId; - - string featureFileName; - measurementsFile >> featureFileName; - vector features = readFeatures(poseId, (baseFolder+featureFileName).c_str()); - allFeatures[poseId] = features; - } - - return allFeatures; -} diff --git a/examples/vSLAMexample/vSLAMutils.h b/examples/vSLAMexample/vSLAMutils.h deleted file mode 100644 index 52d492224..000000000 --- a/examples/vSLAMexample/vSLAMutils.h +++ /dev/null @@ -1,37 +0,0 @@ -/* ---------------------------------------------------------------------------- - - * GTSAM Copyright 2010, Georgia Tech Research Corporation, - * Atlanta, Georgia 30332-0415 - * All Rights Reserved - * Authors: Frank Dellaert, et al. (see THANKS for the full author list) - - * See LICENSE for the license information - - * -------------------------------------------------------------------------- */ - -/** - * @file Feature2D.cpp - * @brief - * @author Duy-Nguyen Ta - */ - -#pragma once - -#include -#include -#include "Feature2D.h" -#include "gtsam/geometry/Pose3.h" -#include "gtsam/geometry/Point3.h" -#include "gtsam/geometry/Cal3_S2.h" - - -std::map readLandMarks(const std::string& landmarkFile); - -gtsam::Pose3 readPose(const char* poseFn); -std::map readPoses(const std::string& baseFolder, const std::string& posesFN); - -gtsam::shared_ptrK readCalibData(const std::string& calibFn); - -std::vector readFeatureFile(const char* filename); -std::vector readAllMeasurements(const std::string& baseFolder, const std::string& measurementsFn); -std::map > readAllMeasurementsISAM(const std::string& baseFolder, const std::string& measurementsFn); diff --git a/gtsam.h b/gtsam.h index e80a37a0b..2015705ae 100644 --- a/gtsam.h +++ b/gtsam.h @@ -9,7 +9,7 @@ * Only one Method/Constructor per line * Methods can return * - Eigen types: Matrix, Vector - * - C/C++ basic types: string, bool, size_t, int, double, char + * - C/C++ basic types: string, bool, size_t, size_t, double, char * - void * - Any class with which be copied with boost::make_shared() * - boost::shared_ptr of any object type @@ -19,7 +19,7 @@ * Arguments to functions any of * - Eigen types: Matrix, Vector * - Eigen types and classes as an optionally const reference - * - C/C++ basic types: string, bool, size_t, int, double + * - C/C++ basic types: string, bool, size_t, size_t, double, char * - Any class with which be copied with boost::make_shared() (except Eigen) * - boost::shared_ptr of any object type (except Eigen) * Comments can use either C++ or C style, with multiple lines @@ -68,17 +68,29 @@ namespace gtsam { //************************************************************************* class Point2 { - Point2(); - Point2(double x, double y); - static gtsam::Point2 Expmap(Vector v); + Point2(); + Point2(double x, double y); + static gtsam::Point2 Expmap(Vector v); static Vector Logmap(const gtsam::Point2& p); void print(string s) const; double x(); double y(); - Vector localCoordinates(const gtsam::Point2& p); + Vector localCoordinates(const gtsam::Point2& p); gtsam::Point2 compose(const gtsam::Point2& p2); gtsam::Point2 between(const gtsam::Point2& p2); - gtsam::Point2 retract(Vector v); + gtsam::Point2 retract(Vector v); +}; + +class StereoPoint2 { + StereoPoint2(); + StereoPoint2(double uL, double uR, double v); + static gtsam::StereoPoint2 Expmap(Vector v); + static Vector Logmap(const gtsam::StereoPoint2& p); + void print(string s) const; + Vector localCoordinates(const gtsam::StereoPoint2& p); + gtsam::StereoPoint2 compose(const gtsam::StereoPoint2& p2); + gtsam::StereoPoint2 between(const gtsam::StereoPoint2& p2); + gtsam::StereoPoint2 retract(Vector v); }; class Point3 { @@ -124,22 +136,22 @@ class Rot2 { class Rot3 { Rot3(); Rot3(Matrix R); - static gtsam::Rot3 Rx(double t); - static gtsam::Rot3 Ry(double t); - static gtsam::Rot3 Rz(double t); + static gtsam::Rot3 Rx(double t); + static gtsam::Rot3 Ry(double t); + static gtsam::Rot3 Rz(double t); // static gtsam::Rot3 RzRyRx(double x, double y, double z); // FIXME: overloaded functions don't work yet - static gtsam::Rot3 RzRyRx(Vector xyz); - static gtsam::Rot3 yaw (double t); // positive yaw is to right (as in aircraft heading) - static gtsam::Rot3 pitch(double t); // positive pitch is up (increasing aircraft altitude) - static gtsam::Rot3 roll (double t); // positive roll is to right (increasing yaw in aircraft) - static gtsam::Rot3 ypr(double y, double p, double r); - static gtsam::Rot3 quaternion(double w, double x, double y, double z); - static gtsam::Rot3 rodriguez(Vector v); + static gtsam::Rot3 RzRyRx(Vector xyz); + static gtsam::Rot3 yaw(double t); // positive yaw is to right (as in aircraft heading) + static gtsam::Rot3 pitch(double t); // positive pitch is up (increasing aircraft altitude) + static gtsam::Rot3 roll(double t); // positive roll is to right (increasing yaw in aircraft) + static gtsam::Rot3 ypr(double y, double p, double r); + static gtsam::Rot3 quaternion(double w, double x, double y, double z); + static gtsam::Rot3 rodriguez(Vector v); void print(string s) const; bool equals(const gtsam::Rot3& rot, double tol) const; - static gtsam::Rot3 identity(); - gtsam::Rot3 compose(const gtsam::Rot3& p2) const; - gtsam::Rot3 inverse() const; + static gtsam::Rot3 identity(); + gtsam::Rot3 compose(const gtsam::Rot3& p2) const; + gtsam::Rot3 inverse() const; gtsam::Rot3 between(const gtsam::Rot3& p2) const; gtsam::Point3 rotate(const gtsam::Point3& p) const; gtsam::Point3 unrotate(const gtsam::Point3& p) const; @@ -150,13 +162,13 @@ class Rot3 { static Vector Logmap(const gtsam::Rot3& p); Matrix matrix() const; Matrix transpose() const; - gtsam::Point3 column(int index) const; + gtsam::Point3 column(size_t index) const; Vector xyz() const; Vector ypr() const; Vector rpy() const; - double roll() const; - double pitch() const; - double yaw() const; + double roll() const; + double pitch() const; + double yaw() const; // Vector toQuaternion() const; // FIXME: Can't cast to Vector properly }; @@ -173,7 +185,7 @@ class Pose2 { double x() const; double y() const; double theta() const; - int dim() const; + size_t dim() const; Vector localCoordinates(const gtsam::Pose2& p); gtsam::Pose2 retract(Vector v); gtsam::Pose2 compose(const gtsam::Pose2& p2); @@ -185,47 +197,86 @@ class Pose2 { }; class Pose3 { + // Standard Constructors Pose3(); + Pose3(const gtsam::Pose3& pose); Pose3(const gtsam::Rot3& r, const gtsam::Point3& t); - Pose3(Matrix t); Pose3(const gtsam::Pose2& pose2); - static gtsam::Pose3 Expmap(Vector v); - static Vector Logmap(const gtsam::Pose3& p); + Pose3(Matrix t); + + // Testable void print(string s) const; bool equals(const gtsam::Pose3& pose, double tol) const; + + // Group + static gtsam::Pose3 identity(); + gtsam::Pose3 inverse(); + gtsam::Pose3 compose(const gtsam::Pose3& p2); + gtsam::Pose3 between(const gtsam::Pose3& p2); + + // Manifold + static size_t Dim(); + size_t dim() const; + gtsam::Pose3 retract(Vector v); + gtsam::Pose3 retractFirstOrder(Vector v); + Vector localCoordinates(const gtsam::Pose3& T2) const; + + // Lie Group + static gtsam::Pose3 Expmap(Vector v); + static Vector Logmap(const gtsam::Pose3& p); + Matrix adjointMap() const; + Vector adjoint(const Vector& xi) const; + static Matrix wedge(double wx, double wy, double wz, double vx, double vy, double vz); + + // Group Action on Point3 + gtsam::Point3 transform_from(const gtsam::Point3& p) const; + gtsam::Point3 transform_to(const gtsam::Point3& p) const; + + // Standard Interface + gtsam::Rot3 rotation() const; + gtsam::Point3 translation() const; double x() const; double y() const; double z() const; Matrix matrix() const; - Matrix adjointMap() const; - gtsam::Pose3 compose(const gtsam::Pose3& p2); - gtsam::Pose3 between(const gtsam::Pose3& p2); - gtsam::Pose3 retract(Vector v); - gtsam::Pose3 retractFirstOrder(Vector v); - Vector localCoordinates(const gtsam::Pose3& T2) const; - gtsam::Point3 translation() const; - gtsam::Rot3 rotation() const; + gtsam::Pose3 transform_to(const gtsam::Pose3& pose) const; + double range(const gtsam::Point3& point); + // double range(const gtsam::Pose3& pose); +}; + +class Cal3_S2 { + Cal3_S2(); + Cal3_S2(double fx, double fy, double s, double u0, double v0); + + void print(string s) const; +}; + +class Cal3_S2Stereo { + Cal3_S2Stereo(); + Cal3_S2Stereo(double fx, double fy, double s, double u0, double v0, double b); + + void print(string s) const; }; class CalibratedCamera { - - CalibratedCamera(); - CalibratedCamera(const gtsam::Pose3& pose); - CalibratedCamera(const Vector& v); - void print(string s) const; - bool equals(const gtsam::CalibratedCamera& camera, double tol) const; + CalibratedCamera(); + CalibratedCamera(const gtsam::Pose3& pose); + CalibratedCamera(const Vector& v); - gtsam::Pose3 pose() const; + void print(string s) const; + bool equals(const gtsam::CalibratedCamera& camera, double tol) const; - gtsam::CalibratedCamera compose(const gtsam::CalibratedCamera& c) const; - gtsam::CalibratedCamera inverse() const; - gtsam::CalibratedCamera level(const gtsam::Pose2& pose2, double height); - gtsam::CalibratedCamera retract(const Vector& d) const; - Vector localCoordinates(const gtsam::CalibratedCamera& T2) const; + gtsam::Pose3 pose() const; - gtsam::Point2 project(const gtsam::Point3& point) const; - static gtsam::Point2 project_to_camera(const gtsam::Point3& cameraPoint); + gtsam::CalibratedCamera compose(const gtsam::CalibratedCamera& c) const; + gtsam::CalibratedCamera inverse() const; + gtsam::CalibratedCamera level(const gtsam::Pose2& pose2, double height); + gtsam::CalibratedCamera retract(const Vector& d) const; + Vector localCoordinates(const gtsam::CalibratedCamera& T2) const; + + gtsam::Point2 project(const gtsam::Point3& point) const; + static gtsam::Point2 project_to_camera(const gtsam::Point3& cameraPoint); }; @@ -263,25 +314,25 @@ class SharedNoiseModel { class VectorValues { VectorValues(); - VectorValues(int nVars, int varDim); + VectorValues(size_t nVars, size_t varDim); void print(string s) const; bool equals(const gtsam::VectorValues& expected, double tol) const; - int size() const; - void insert(int j, Vector value); + size_t size() const; + void insert(size_t j, Vector value); }; class GaussianConditional { - GaussianConditional(int key, Vector d, Matrix R, Vector sigmas); - GaussianConditional(int key, Vector d, Matrix R, int name1, Matrix S, + GaussianConditional(size_t key, Vector d, Matrix R, Vector sigmas); + GaussianConditional(size_t key, Vector d, Matrix R, size_t name1, Matrix S, Vector sigmas); - GaussianConditional(int key, Vector d, Matrix R, int name1, Matrix S, - int name2, Matrix T, Vector sigmas); + GaussianConditional(size_t key, Vector d, Matrix R, size_t name1, Matrix S, + size_t name2, Matrix T, Vector sigmas); void print(string s) const; bool equals(const gtsam::GaussianConditional &cg, double tol) const; }; class GaussianDensity { - GaussianDensity(int key, Vector d, Matrix R, Vector sigmas); + GaussianDensity(size_t key, Vector d, Matrix R, Vector sigmas); void print(string s) const; Vector mean() const; Matrix information() const; @@ -305,10 +356,11 @@ class GaussianFactor { class JacobianFactor { JacobianFactor(); JacobianFactor(Vector b_in); - JacobianFactor(int i1, Matrix A1, Vector b, const gtsam::SharedDiagonal& model); - JacobianFactor(int i1, Matrix A1, int i2, Matrix A2, Vector b, + JacobianFactor(size_t i1, Matrix A1, Vector b, const gtsam::SharedDiagonal& model); - JacobianFactor(int i1, Matrix A1, int i2, Matrix A2, int i3, Matrix A3, + JacobianFactor(size_t i1, Matrix A1, size_t i2, Matrix A2, Vector b, + const gtsam::SharedDiagonal& model); + JacobianFactor(size_t i1, Matrix A1, size_t i2, Matrix A2, size_t i3, Matrix A3, Vector b, const gtsam::SharedDiagonal& model); void print(string s) const; bool equals(const gtsam::GaussianFactor& lf, double tol) const; @@ -321,38 +373,38 @@ class JacobianFactor { class HessianFactor { HessianFactor(const gtsam::HessianFactor& gf); HessianFactor(); - HessianFactor(int j, Matrix G, Vector g, double f); - HessianFactor(int j, Vector mu, Matrix Sigma); - HessianFactor(int j1, int j2, Matrix G11, Matrix G12, Vector g1, Matrix G22, + HessianFactor(size_t j, Matrix G, Vector g, double f); + HessianFactor(size_t j, Vector mu, Matrix Sigma); + HessianFactor(size_t j1, size_t j2, Matrix G11, Matrix G12, Vector g1, Matrix G22, Vector g2, double f); - HessianFactor(int j1, int j2, int j3, Matrix G11, Matrix G12, Matrix G13, + HessianFactor(size_t j1, size_t j2, size_t j3, Matrix G11, Matrix G12, Matrix G13, Vector g1, Matrix G22, Matrix G23, Vector g2, Matrix G33, Vector g3, double f); HessianFactor(const gtsam::GaussianConditional& cg); HessianFactor(const gtsam::GaussianFactor& factor); - void print(string s) const; - bool equals(const gtsam::GaussianFactor& lf, double tol) const; - double error(const gtsam::VectorValues& c) const; + void print(string s) const; + bool equals(const gtsam::GaussianFactor& lf, double tol) const; + double error(const gtsam::VectorValues& c) const; }; class GaussianFactorGraph { GaussianFactorGraph(); - GaussianFactorGraph(const gtsam::GaussianBayesNet& CBN); + GaussianFactorGraph(const gtsam::GaussianBayesNet& CBN); - // From FactorGraph + // From FactorGraph void push_back(gtsam::GaussianFactor* factor); void print(string s) const; bool equals(const gtsam::GaussianFactorGraph& lfgraph, double tol) const; - int size() const; + size_t size() const; // Building the graph void add(gtsam::JacobianFactor* factor); // all these won't work as MATLAB can't handle overloading // void add(Vector b); -// void add(int key1, Matrix A1, Vector b, const gtsam::SharedDiagonal& model); -// void add(int key1, Matrix A1, int key2, Matrix A2, Vector b, +// void add(size_t key1, Matrix A1, Vector b, const gtsam::SharedDiagonal& model); +// void add(size_t key1, Matrix A1, size_t key2, Matrix A2, Vector b, // const gtsam::SharedDiagonal& model); -// void add(int key1, Matrix A1, int key2, Matrix A2, int key3, Matrix A3, +// void add(size_t key1, Matrix A1, size_t key2, Matrix A2, size_t key3, Matrix A3, // Vector b, const gtsam::SharedDiagonal& model); // void add(gtsam::HessianFactor* factor); @@ -361,8 +413,9 @@ class GaussianFactorGraph { double probPrime(const gtsam::VectorValues& c) const; // combining - static gtsam::GaussianFactorGraph combine2(const gtsam::GaussianFactorGraph& lfg1, - const gtsam::GaussianFactorGraph& lfg2); + static gtsam::GaussianFactorGraph combine2( + const gtsam::GaussianFactorGraph& lfg1, + const gtsam::GaussianFactorGraph& lfg2); void combine(const gtsam::GaussianFactorGraph& lfg); // Conversion to matrices @@ -372,11 +425,12 @@ class GaussianFactorGraph { }; class GaussianSequentialSolver { - GaussianSequentialSolver(const gtsam::GaussianFactorGraph& graph, bool useQR); - gtsam::GaussianBayesNet* eliminate() const; - gtsam::VectorValues* optimize() const; - gtsam::GaussianFactor* marginalFactor(int j) const; - Matrix marginalCovariance(int j) const; + GaussianSequentialSolver(const gtsam::GaussianFactorGraph& graph, + bool useQR); + gtsam::GaussianBayesNet* eliminate() const; + gtsam::VectorValues* optimize() const; + gtsam::GaussianFactor* marginalFactor(size_t j) const; + Matrix marginalCovariance(size_t j) const; }; class KalmanFilter { @@ -384,17 +438,17 @@ class KalmanFilter { // gtsam::GaussianDensity* init(Vector x0, const gtsam::SharedDiagonal& P0); gtsam::GaussianDensity* init(Vector x0, Matrix P0); void print(string s) const; - static int step(gtsam::GaussianDensity* p); - gtsam::GaussianDensity* predict(gtsam::GaussianDensity* p, Matrix F, Matrix B, Vector u, - const gtsam::SharedDiagonal& modelQ); - gtsam::GaussianDensity* predictQ(gtsam::GaussianDensity* p, Matrix F, Matrix B, Vector u, - Matrix Q); - gtsam::GaussianDensity* predict2(gtsam::GaussianDensity* p, Matrix A0, Matrix A1, Vector b, - const gtsam::SharedDiagonal& model); - gtsam::GaussianDensity* update(gtsam::GaussianDensity* p, Matrix H, Vector z, - const gtsam::SharedDiagonal& model); - gtsam::GaussianDensity* updateQ(gtsam::GaussianDensity* p, Matrix H, Vector z, - Matrix Q); + static size_t step(gtsam::GaussianDensity* p); + gtsam::GaussianDensity* predict(gtsam::GaussianDensity* p, Matrix F, + Matrix B, Vector u, const gtsam::SharedDiagonal& modelQ); + gtsam::GaussianDensity* predictQ(gtsam::GaussianDensity* p, Matrix F, + Matrix B, Vector u, Matrix Q); + gtsam::GaussianDensity* predict2(gtsam::GaussianDensity* p, Matrix A0, + Matrix A1, Vector b, const gtsam::SharedDiagonal& model); + gtsam::GaussianDensity* update(gtsam::GaussianDensity* p, Matrix H, + Vector z, const gtsam::SharedDiagonal& model); + gtsam::GaussianDensity* updateQ(gtsam::GaussianDensity* p, Matrix H, + Vector z, Matrix Q); }; //************************************************************************* @@ -402,9 +456,9 @@ class KalmanFilter { //************************************************************************* class Symbol { - Symbol(char c, size_t j); + Symbol(char c, size_t j); void print(string s) const; - size_t key() const; + size_t key() const; }; class Ordering { @@ -415,24 +469,121 @@ class Ordering { }; class NonlinearFactorGraph { - NonlinearFactorGraph(); + NonlinearFactorGraph(); }; class Values { - Values(); - void print(string s) const; - bool exists(size_t j) const; + Values(); + size_t size() const; + void print(string s) const; + bool exists(size_t j) const; }; class Marginals { - Marginals(const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& solution); - void print(string s) const; - Matrix marginalCovariance(size_t variable) const; - Matrix marginalInformation(size_t variable) const; + Marginals(const gtsam::NonlinearFactorGraph& graph, + const gtsam::Values& solution); + void print(string s) const; + Matrix marginalCovariance(size_t variable) const; + Matrix marginalInformation(size_t variable) const; }; }///\namespace gtsam +//************************************************************************* +// Pose2SLAM +//************************************************************************* + +#include +namespace pose2SLAM { + +class Values { + Values(); + size_t size() const; + void print(string s) const; + static pose2SLAM::Values Circle(size_t n, double R); + void insertPose(size_t key, const gtsam::Pose2& pose); + gtsam::Pose2 pose(size_t i); + Vector xs() const; + Vector ys() const; + Vector thetas() const; +}; + +class Graph { + Graph(); + + // FactorGraph + void print(string s) const; + bool equals(const pose2SLAM::Graph& fg, double tol) const; + size_t size() const; + bool empty() const; + void remove(size_t i); + size_t nrFactors() const; + + // NonlinearFactorGraph + double error(const pose2SLAM::Values& values) const; + double probPrime(const pose2SLAM::Values& values) const; + gtsam::Ordering* orderingCOLAMD(const pose2SLAM::Values& values) const; + gtsam::GaussianFactorGraph* linearize(const pose2SLAM::Values& values, + const gtsam::Ordering& ordering) const; + + // pose2SLAM-specific + void addPrior(size_t key, const gtsam::Pose2& pose, const gtsam::SharedNoiseModel& noiseModel); + void addPoseConstraint(size_t key, const gtsam::Pose2& pose); + void addOdometry(size_t key1, size_t key2, const gtsam::Pose2& odometry, const gtsam::SharedNoiseModel& noiseModel); + void addConstraint(size_t key1, size_t key2, const gtsam::Pose2& odometry, const gtsam::SharedNoiseModel& noiseModel); + pose2SLAM::Values optimize(const pose2SLAM::Values& initialEstimate) const; + gtsam::Marginals marginals(const pose2SLAM::Values& solution) const; +}; + +}///\namespace pose2SLAM + +//************************************************************************* +// Pose3SLAM +//************************************************************************* + +#include +namespace pose3SLAM { + +class Values { + Values(); + size_t size() const; + void print(string s) const; + static pose3SLAM::Values Circle(size_t n, double R); + void insertPose(size_t key, const gtsam::Pose3& pose); + gtsam::Pose3 pose(size_t i); + Vector xs() const; + Vector ys() const; + Vector zs() const; +}; + +class Graph { + Graph(); + + // FactorGraph + void print(string s) const; + bool equals(const pose3SLAM::Graph& fg, double tol) const; + size_t size() const; + bool empty() const; + void remove(size_t i); + size_t nrFactors() const; + + // NonlinearFactorGraph + double error(const pose3SLAM::Values& values) const; + double probPrime(const pose3SLAM::Values& values) const; + gtsam::Ordering* orderingCOLAMD(const pose3SLAM::Values& values) const; + gtsam::GaussianFactorGraph* linearize(const pose3SLAM::Values& values, + const gtsam::Ordering& ordering) const; + + // pose3SLAM-specific + void addPrior(size_t key, const gtsam::Pose3& p, const gtsam::SharedNoiseModel& model); + void addConstraint(size_t key1, size_t key2, const gtsam::Pose3& z, const gtsam::SharedNoiseModel& model); + void addHardConstraint(size_t i, const gtsam::Pose3& p); + pose3SLAM::Values optimize(const pose3SLAM::Values& initialEstimate) const; + gtsam::Marginals marginals(const pose3SLAM::Values& solution) const; +}; + +}///\namespace pose3SLAM + //************************************************************************* // planarSLAM //************************************************************************* @@ -442,75 +593,53 @@ namespace planarSLAM { class Values { Values(); + size_t size() const; void print(string s) const; - gtsam::Pose2 pose(int key) const; - gtsam::Point2 point(int key) const; - void insertPose(int key, const gtsam::Pose2& pose); - void insertPoint(int key, const gtsam::Point2& point); + void insertPose(size_t key, const gtsam::Pose2& pose); + void insertPoint(size_t key, const gtsam::Point2& point); + gtsam::Pose2 pose(size_t key) const; + gtsam::Point2 point(size_t key) const; }; class Graph { Graph(); + // FactorGraph void print(string s) const; + bool equals(const planarSLAM::Graph& fg, double tol) const; + size_t size() const; + bool empty() const; + void remove(size_t i); + size_t nrFactors() const; + // NonlinearFactorGraph double error(const planarSLAM::Values& values) const; + double probPrime(const planarSLAM::Values& values) const; gtsam::Ordering* orderingCOLAMD(const planarSLAM::Values& values) const; gtsam::GaussianFactorGraph* linearize(const planarSLAM::Values& values, const gtsam::Ordering& ordering) const; - void addPrior(int key, const gtsam::Pose2& pose, const gtsam::SharedNoiseModel& noiseModel); - void addPoseConstraint(int key, const gtsam::Pose2& pose); - void addOdometry(int key1, int key2, const gtsam::Pose2& odometry, const gtsam::SharedNoiseModel& noiseModel); - void addBearing(int poseKey, int pointKey, const gtsam::Rot2& bearing, const gtsam::SharedNoiseModel& noiseModel); - void addRange(int poseKey, int pointKey, double range, const gtsam::SharedNoiseModel& noiseModel); - void addBearingRange(int poseKey, int pointKey, const gtsam::Rot2& bearing, double range, - const gtsam::SharedNoiseModel& noiseModel); + // planarSLAM-specific + void addPrior(size_t key, const gtsam::Pose2& pose, const gtsam::SharedNoiseModel& noiseModel); + void addPoseConstraint(size_t key, const gtsam::Pose2& pose); + void addOdometry(size_t key1, size_t key2, const gtsam::Pose2& odometry, const gtsam::SharedNoiseModel& noiseModel); + void addBearing(size_t poseKey, size_t pointKey, const gtsam::Rot2& bearing, const gtsam::SharedNoiseModel& noiseModel); + void addRange(size_t poseKey, size_t pointKey, double range, const gtsam::SharedNoiseModel& noiseModel); + void addBearingRange(size_t poseKey, size_t pointKey, const gtsam::Rot2& bearing,double range, const gtsam::SharedNoiseModel& noiseModel); planarSLAM::Values optimize(const planarSLAM::Values& initialEstimate); + gtsam::Marginals marginals(const planarSLAM::Values& solution) const; }; class Odometry { - Odometry(int key1, int key2, const gtsam::Pose2& measured, + Odometry(size_t key1, size_t key2, const gtsam::Pose2& measured, const gtsam::SharedNoiseModel& model); void print(string s) const; - gtsam::GaussianFactor* linearize(const planarSLAM::Values& center, const gtsam::Ordering& ordering) const; + gtsam::GaussianFactor* linearize(const planarSLAM::Values& center, + const gtsam::Ordering& ordering) const; }; }///\namespace planarSLAM -//************************************************************************* -// Pose2SLAM -//************************************************************************* - -#include -namespace pose2SLAM { - -class Values { - Values(); - void print(string s) const; - void insertPose(int key, const gtsam::Pose2& pose); - gtsam::Pose2 pose(int i); -}; - -class Graph { - Graph(); - - void print(string s) const; - - double error(const pose2SLAM::Values& values) const; - gtsam::Ordering* orderingCOLAMD(const pose2SLAM::Values& values) const; - gtsam::GaussianFactorGraph* linearize(const pose2SLAM::Values& values, - const gtsam::Ordering& ordering) const; - - void addPrior(int key, const gtsam::Pose2& pose, const gtsam::SharedNoiseModel& noiseModel); - void addPoseConstraint(int key, const gtsam::Pose2& pose); - void addOdometry(int key1, int key2, const gtsam::Pose2& odometry, const gtsam::SharedNoiseModel& noiseModel); - pose2SLAM::Values optimize(const pose2SLAM::Values& initialEstimate) const; - gtsam::Marginals marginals(const pose2SLAM::Values& solution) const; -}; - -}///\namespace pose2SLAM - //************************************************************************* // Simulated2D //************************************************************************* @@ -520,12 +649,12 @@ namespace simulated2D { class Values { Values(); - void insertPose(int i, const gtsam::Point2& p); - void insertPoint(int j, const gtsam::Point2& p); - int nrPoses() const; - int nrPoints() const; - gtsam::Point2 pose(int i); - gtsam::Point2 point(int j); + void insertPose(size_t i, const gtsam::Point2& p); + void insertPoint(size_t j, const gtsam::Point2& p); + size_t nrPoses() const; + size_t nrPoints() const; + gtsam::Point2 pose(size_t i); + gtsam::Point2 point(size_t j); }; class Graph { @@ -542,12 +671,12 @@ namespace simulated2DOriented { class Values { Values(); - void insertPose(int i, const gtsam::Pose2& p); - void insertPoint(int j, const gtsam::Point2& p); - int nrPoses() const; - int nrPoints() const; - gtsam::Pose2 pose(int i); - gtsam::Point2 point(int j); + void insertPose(size_t i, const gtsam::Pose2& p); + void insertPoint(size_t j, const gtsam::Point2& p); + size_t nrPoses() const; + size_t nrPoints() const; + gtsam::Pose2 pose(size_t i); + gtsam::Point2 point(size_t j); }; class Graph { @@ -557,3 +686,51 @@ class Graph { // TODO: add factors, etc. }///\namespace simulated2DOriented + +//************************************************************************* +// VisualSLAM +//************************************************************************* + +#include +namespace visualSLAM { + +class Values { + Values(); + void insertPose(size_t key, const gtsam::Pose3& pose); + void insertPoint(size_t key, const gtsam::Point3& pose); + size_t size() const; + void print(string s) const; + gtsam::Pose3 pose(size_t i); + gtsam::Point3 point(size_t j); +}; + +class Graph { + Graph(); + + void print(string s) const; + + double error(const visualSLAM::Values& values) const; + gtsam::Ordering* orderingCOLAMD(const visualSLAM::Values& values) const; + gtsam::GaussianFactorGraph* linearize(const visualSLAM::Values& values, + const gtsam::Ordering& ordering) const; + + // Measurements + void addMeasurement(const gtsam::Point2& measured, const gtsam::SharedNoiseModel& model, + size_t poseKey, size_t pointKey, const gtsam::Cal3_S2* K); + void addStereoMeasurement(const gtsam::StereoPoint2& measured, const gtsam::SharedNoiseModel& model, + size_t poseKey, size_t pointKey, const gtsam::Cal3_S2Stereo* K); + + // Constraints + void addPoseConstraint(size_t poseKey, const gtsam::Pose3& p); + void addPointConstraint(size_t pointKey, const gtsam::Point3& p); + + // Priors + void addPosePrior(size_t poseKey, const gtsam::Pose3& p, const gtsam::SharedNoiseModel& model); + void addPointPrior(size_t pointKey, const gtsam::Point3& p, const gtsam::SharedNoiseModel& model); + void addRangeFactor(size_t poseKey, size_t pointKey, double range, const gtsam::SharedNoiseModel& model); + + visualSLAM::Values optimize(const visualSLAM::Values& initialEstimate) const; + gtsam::Marginals marginals(const visualSLAM::Values& solution) const; +}; + +}///\namespace visualSLAM diff --git a/gtsam/inference/BayesNet.h b/gtsam/inference/BayesNet.h index 0f78a15e3..f6721816c 100644 --- a/gtsam/inference/BayesNet.h +++ b/gtsam/inference/BayesNet.h @@ -10,7 +10,7 @@ * -------------------------------------------------------------------------- */ /** - * @file BayesNet + * @file BayesNet.h * @brief Bayes network * @author Frank Dellaert */ diff --git a/gtsam/inference/BayesTree-inl.h b/gtsam/inference/BayesTree-inl.h index 00cd38609..2c3ce4035 100644 --- a/gtsam/inference/BayesTree-inl.h +++ b/gtsam/inference/BayesTree-inl.h @@ -10,7 +10,7 @@ * -------------------------------------------------------------------------- */ /** - * @file BayesTree.cpp + * @file BayesTree-inl.h * @brief Bayes Tree is a tree of cliques of a Bayes Chain * @author Frank Dellaert * @author Michael Kaess diff --git a/gtsam/inference/BayesTree.h b/gtsam/inference/BayesTree.h index a9ed53ee9..a4cdbaafe 100644 --- a/gtsam/inference/BayesTree.h +++ b/gtsam/inference/BayesTree.h @@ -10,7 +10,7 @@ * -------------------------------------------------------------------------- */ /** - * @file BayesTree + * @file BayesTree.h * @brief Bayes Tree is a tree of cliques of a Bayes Chain * @author Frank Dellaert */ diff --git a/gtsam/inference/BayesTreeCliqueBase-inl.h b/gtsam/inference/BayesTreeCliqueBase-inl.h index dfc8864f7..c57d6ed50 100644 --- a/gtsam/inference/BayesTreeCliqueBase-inl.h +++ b/gtsam/inference/BayesTreeCliqueBase-inl.h @@ -10,7 +10,7 @@ * -------------------------------------------------------------------------- */ /** - * @file BayesTreeCliqueBase + * @file BayesTreeCliqueBase-inl.h * @brief Base class for cliques of a BayesTree * @author Richard Roberts and Frank Dellaert */ diff --git a/gtsam/inference/BayesTreeCliqueBase.h b/gtsam/inference/BayesTreeCliqueBase.h index 194b616b7..7ae2c15f9 100644 --- a/gtsam/inference/BayesTreeCliqueBase.h +++ b/gtsam/inference/BayesTreeCliqueBase.h @@ -10,7 +10,7 @@ * -------------------------------------------------------------------------- */ /** - * @file BayesTreeCliqueBase + * @file BayesTreeCliqueBase.h * @brief Base class for cliques of a BayesTree * @author Richard Roberts and Frank Dellaert */ diff --git a/gtsam/inference/EliminationTree-inl.h b/gtsam/inference/EliminationTree-inl.h index 488911127..e5f50a867 100644 --- a/gtsam/inference/EliminationTree-inl.h +++ b/gtsam/inference/EliminationTree-inl.h @@ -10,7 +10,7 @@ * -------------------------------------------------------------------------- */ /** - * @file EliminationTree.cpp + * @file EliminationTree-inl.h * @author Frank Dellaert * @date Oct 13, 2010 */ diff --git a/gtsam/inference/graph-inl.h b/gtsam/inference/graph-inl.h index f9f8aa07c..c4485cf5c 100644 --- a/gtsam/inference/graph-inl.h +++ b/gtsam/inference/graph-inl.h @@ -10,9 +10,9 @@ * -------------------------------------------------------------------------- */ /* - * graph-inl.h + * @file graph-inl.h * @brief Graph algorithm using boost library - * @author: Kai Ni + * @author Kai Ni */ #pragma once diff --git a/gtsam/inference/inference.cpp b/gtsam/inference/inference.cpp index 9b7252030..7afad8330 100644 --- a/gtsam/inference/inference.cpp +++ b/gtsam/inference/inference.cpp @@ -10,9 +10,10 @@ * -------------------------------------------------------------------------- */ /** - * @file inference-inl.h + * @file inference.cpp * @brief inference definitions - * @author Frank Dellaert, Richard Roberts + * @author Frank Dellaert + * @author Richard Roberts */ #include diff --git a/gtsam/inference/inference.h b/gtsam/inference/inference.h index d87720b5a..38f896a0f 100644 --- a/gtsam/inference/inference.h +++ b/gtsam/inference/inference.h @@ -13,7 +13,8 @@ * @file inference.h * @brief Contains *generic* inference algorithms that convert between templated * graphical models, i.e., factor graphs, Bayes nets, and Bayes trees - * @author Frank Dellaert, Richard Roberts + * @author Frank Dellaert + * @author Richard Roberts */ #pragma once diff --git a/gtsam/linear/GaussianBayesTree-inl.h b/gtsam/linear/GaussianBayesTree-inl.h index 4972b13bf..4e398ef7f 100644 --- a/gtsam/linear/GaussianBayesTree-inl.h +++ b/gtsam/linear/GaussianBayesTree-inl.h @@ -10,7 +10,7 @@ * -------------------------------------------------------------------------- */ /** - * @file GaussianBayesTree.cpp + * @file GaussianBayesTree-inl.h * @brief Gaussian Bayes Tree, the result of eliminating a GaussianJunctionTree * @brief GaussianBayesTree * @author Frank Dellaert diff --git a/gtsam/linear/GaussianISAM.cpp b/gtsam/linear/GaussianISAM.cpp index 6207d6ac7..f78d8b3c3 100644 --- a/gtsam/linear/GaussianISAM.cpp +++ b/gtsam/linear/GaussianISAM.cpp @@ -10,7 +10,7 @@ * -------------------------------------------------------------------------- */ /** - * @file GaussianISAM + * @file GaussianISAM.cpp * @brief Linear ISAM only * @author Michael Kaess */ diff --git a/gtsam/linear/GaussianISAM.h b/gtsam/linear/GaussianISAM.h index af96d5317..e4ac62704 100644 --- a/gtsam/linear/GaussianISAM.h +++ b/gtsam/linear/GaussianISAM.h @@ -10,7 +10,7 @@ * -------------------------------------------------------------------------- */ /** - * @file GaussianISAM + * @file GaussianISAM.h * @brief Linear ISAM only * @author Michael Kaess */ diff --git a/gtsam/linear/GaussianSequentialSolver.cpp b/gtsam/linear/GaussianSequentialSolver.cpp index b83926647..d3ff3146c 100644 --- a/gtsam/linear/GaussianSequentialSolver.cpp +++ b/gtsam/linear/GaussianSequentialSolver.cpp @@ -10,7 +10,7 @@ * -------------------------------------------------------------------------- */ /** - * @file SequentialSolver.cpp + * @file GaussianSequentialSolver.cpp * @author Richard Roberts * @date Oct 19, 2010 */ diff --git a/gtsam/linear/GaussianSequentialSolver.h b/gtsam/linear/GaussianSequentialSolver.h index 2fad97867..36e93bcf4 100644 --- a/gtsam/linear/GaussianSequentialSolver.h +++ b/gtsam/linear/GaussianSequentialSolver.h @@ -10,7 +10,7 @@ * -------------------------------------------------------------------------- */ /** - * @file SequentialSolver.h + * @file GaussianSequentialSolver.h * @brief Solves a GaussianFactorGraph (i.e. a sparse linear system) using sequential variable elimination. * @author Richard Roberts * @date Oct 19, 2010 diff --git a/gtsam/linear/IterativeOptimizationParameters.h b/gtsam/linear/IterativeOptimizationParameters.h index b38f6ab1a..f6b1877ce 100644 --- a/gtsam/linear/IterativeOptimizationParameters.h +++ b/gtsam/linear/IterativeOptimizationParameters.h @@ -96,7 +96,7 @@ struct PreconditionerParameters { enum Verbosity { SILENT = 0, COMPLEXITY = 1, ERROR = 2} verbosity_ ; /* Verbosity */ - PreconditionerParameters(): kernel_(CHOLMOD), type_(Combinatorial), verbosity_(SILENT) {} + PreconditionerParameters(): kernel_(GTSAM), type_(Combinatorial), verbosity_(SILENT) {} PreconditionerParameters(Kernel kernel, const CombinatorialParameters &combinatorial, Verbosity verbosity) : kernel_(kernel), type_(Combinatorial), combinatorial_(combinatorial), verbosity_(verbosity) {} @@ -180,13 +180,13 @@ public: PreconditionerParameters preconditioner_; ConjugateGradientParameters cg_; - enum Kernel { PCG = 0 /*, PCGPlus*/, LSPCG } kernel_ ; /* Iterative Method Kernel */ + enum Kernel { PCG = 0, LSPCG } kernel_ ; /* Iterative Method Kernel */ enum Verbosity { SILENT = 0, COMPLEXITY = 1, ERROR = 2} verbosity_ ; /* Verbosity */ public: IterativeOptimizationParameters() - : preconditioner_(), cg_(), kernel_(PCG), verbosity_(SILENT) {} + : preconditioner_(), cg_(), kernel_(LSPCG), verbosity_(SILENT) {} IterativeOptimizationParameters(const IterativeOptimizationParameters &p) : preconditioner_(p.preconditioner_), cg_(p.cg_), kernel_(p.kernel_), verbosity_(p.verbosity_) {} diff --git a/gtsam/linear/IterativeSolver.h b/gtsam/linear/IterativeSolver.h index 7b1c1e630..9b07d8e07 100644 --- a/gtsam/linear/IterativeSolver.h +++ b/gtsam/linear/IterativeSolver.h @@ -9,18 +9,11 @@ * -------------------------------------------------------------------------- */ -/** - * @file IterativeSolver.h - * @date Oct 24, 2010 - * @author Yong-Dian Jian - * @brief Base Class for all iterative solvers of linear systems - */ - #pragma once -#include #include #include +#include namespace gtsam { @@ -46,7 +39,7 @@ public: virtual VectorValues::shared_ptr optimize () = 0; - Parameters::shared_ptr parameters() { return parameters_ ; } + inline Parameters::shared_ptr parameters() { return parameters_ ; } }; } diff --git a/gtsam/linear/KalmanFilter.h b/gtsam/linear/KalmanFilter.h index b74a0db7d..6df029b61 100644 --- a/gtsam/linear/KalmanFilter.h +++ b/gtsam/linear/KalmanFilter.h @@ -10,11 +10,8 @@ * -------------------------------------------------------------------------- */ /** - * @file testKalmanFilter.cpp - * - * Simple linear Kalman filter. - * Implemented using factor graphs, i.e., does Cholesky-based SRIF, really. - * + * @file KalmanFilter.h + * @brief Simple linear Kalman filter. Implemented using factor graphs, i.e., does Cholesky-based SRIF, really. * @date Sep 3, 2011 * @author Stephen Williams * @author Frank Dellaert diff --git a/gtsam/linear/SimpleSPCGSolver.cpp b/gtsam/linear/SimpleSPCGSolver.cpp new file mode 100644 index 000000000..e7cef9e64 --- /dev/null +++ b/gtsam/linear/SimpleSPCGSolver.cpp @@ -0,0 +1,231 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace gtsam { + +/* utility function */ +std::vector extractRowSpec_(const FactorGraph& jfg) { + std::vector spec; spec.reserve(jfg.size()); + BOOST_FOREACH ( const JacobianFactor::shared_ptr &jf, jfg ) { + spec.push_back(jf->rows()); + } + return spec; +} + +std::vector extractColSpec_(const FactorGraph& gfg, const VariableIndex &index) { + const size_t n = index.size(); + std::vector spec(n, 0); + for ( Index i = 0 ; i < n ; ++i ) { + const GaussianFactor &gf = *(gfg[index[i].front()]); + for ( GaussianFactor::const_iterator it = gf.begin() ; it != gf.end() ; ++it ) { + spec[*it] = gf.getDim(it); + } + } + return spec; +} + +SimpleSPCGSolver::SimpleSPCGSolver(const GaussianFactorGraph &gfg, const Parameters::shared_ptr ¶meters) + : Base(parameters) +{ + std::vector colSpec = extractColSpec_(gfg, VariableIndex(gfg)); + + nVar_ = colSpec.size(); + + /* Split the factor graph into At (tree) and Ac (constraints) + * Note: This part has to be refined for your graph/application */ + GaussianFactorGraph::shared_ptr At; + boost::tie(At, Ac_) = this->splitGraph(gfg); + + /* construct row vector spec of the new system */ + nAc_ = Ac_->size(); + std::vector rowSpec = extractRowSpec_(*Ac_); + for ( Index i = 0 ; i < nVar_ ; ++i ) { + rowSpec.push_back(colSpec[i]); + } + + /* solve the tree with direct solver. get preconditioner */ + Rt_ = EliminationTree::Create(*At)->eliminate(EliminateQR); + xt_ = boost::make_shared(gtsam::optimize(*Rt_)); + + /* initial value for the lspcg method */ + y0_ = boost::make_shared(VectorValues::Zero(colSpec)); + + /* the right hand side of the new system */ + by_ = boost::make_shared(VectorValues::Zero(rowSpec)); + for ( Index i = 0 ; i < nAc_ ; ++i ) { + JacobianFactor::shared_ptr jf = (*Ac_)[i]; + Vector xi = internal::extractVectorValuesSlices(*xt_, jf->begin(), jf->end()); + (*by_)[i] = jf->getb() - jf->getA()*xi; + } + + /* allocate buffer for row and column vectors */ + tmpY_ = boost::make_shared(VectorValues::Zero(colSpec)); + tmpB_ = boost::make_shared(VectorValues::Zero(rowSpec)); +} + +/* implements the CGLS method in Section 7.4 of Bjork's book */ +VectorValues::shared_ptr SimpleSPCGSolver::optimize (const VectorValues &initial) { + + VectorValues::shared_ptr x(new VectorValues(initial)); + VectorValues r = VectorValues::Zero(*by_), + q = VectorValues::Zero(*by_), + p = VectorValues::Zero(*y0_), + s = VectorValues::Zero(*y0_); + + residual(*x, r); + transposeMultiply(r, s) ; + p.vector() = s.vector() ; + + double gamma = s.vector().squaredNorm(), new_gamma = 0.0, alpha = 0.0, beta = 0.0 ; + + const double threshold = + ::max(parameters_->epsilon_abs(), + parameters_->epsilon() * parameters_->epsilon() * gamma); + const size_t iMaxIterations = parameters_->maxIterations(); + + if ( parameters_->verbosity() >= IterativeOptimizationParameters::ERROR ) + cout << "[SimpleSPCGSolver] epsilon = " << parameters_->epsilon() + << ", max = " << parameters_->maxIterations() + << ", ||r0|| = " << std::sqrt(gamma) + << ", threshold = " << threshold << std::endl; + + size_t k ; + for ( k = 1 ; k < iMaxIterations ; ++k ) { + + multiply(p, q); + alpha = gamma / q.vector().squaredNorm() ; + x->vector() += (alpha * p.vector()); + r.vector() -= (alpha * q.vector()); + transposeMultiply(r, s); + new_gamma = s.vector().squaredNorm(); + beta = new_gamma / gamma ; + p.vector() = s.vector() + beta * p.vector(); + gamma = new_gamma ; + + if ( parameters_->verbosity() >= IterativeOptimizationParameters::ERROR) { + cout << "[SimpleSPCGSolver] iteration " << k << ": a = " << alpha << ": b = " << beta << ", ||r|| = " << std::sqrt(gamma) << endl; + } + + if ( gamma < threshold ) break ; + } // k + + if ( parameters_->verbosity() >= IterativeOptimizationParameters::ERROR ) + cout << "[SimpleSPCGSolver] iteration " << k << ": a = " << alpha << ": b = " << beta << ", ||r|| = " << std::sqrt(gamma) << endl; + + /* transform y back to x */ + return this->transform(*x); +} + +void SimpleSPCGSolver::residual(const VectorValues &input, VectorValues &output) { + output.vector() = by_->vector(); + this->multiply(input, *tmpB_); + axpy(-1.0, *tmpB_, output); +} + +void SimpleSPCGSolver::multiply(const VectorValues &input, VectorValues &output) { + this->backSubstitute(input, *tmpY_); + gtsam::multiply(*Ac_, *tmpY_, output); + for ( Index i = 0 ; i < nVar_ ; ++i ) { + output[i + nAc_] = input[i]; + } +} + +void SimpleSPCGSolver::transposeMultiply(const VectorValues &input, VectorValues &output) { + gtsam::transposeMultiply(*Ac_, input, *tmpY_); + this->transposeBackSubstitute(*tmpY_, output); + for ( Index i = 0 ; i < nVar_ ; ++i ) { + output[i] += input[nAc_+i]; + } +} + +void SimpleSPCGSolver::backSubstitute(const VectorValues &input, VectorValues &output) { + for ( Index i = 0 ; i < input.size() ; ++i ) { + output[i] = input[i] ; + } + BOOST_REVERSE_FOREACH(const boost::shared_ptr cg, *Rt_) { + const Index key = *(cg->beginFrontals()); + Vector xS = internal::extractVectorValuesSlices(output, cg->beginParents(), cg->endParents()); + xS = input[key] - cg->get_S() * xS; + output[key] = cg->get_R().triangularView().solve(xS); + } +} + +void SimpleSPCGSolver::transposeBackSubstitute(const VectorValues &input, VectorValues &output) { + for ( Index i = 0 ; i < input.size() ; ++i ) { + output[i] = input[i] ; + } + BOOST_FOREACH(const boost::shared_ptr cg, *Rt_) { + const Index key = *(cg->beginFrontals()); + output[key] = gtsam::backSubstituteUpper(output[key], Matrix(cg->get_R())); + const Vector d = internal::extractVectorValuesSlices(output, cg->beginParents(), cg->endParents()) + - cg->get_S().transpose() * output[key]; + internal::writeVectorValuesSlices(d, output, cg->beginParents(), cg->endParents()); + } +} + +VectorValues::shared_ptr SimpleSPCGSolver::transform(const VectorValues &y) { + VectorValues::shared_ptr x = boost::make_shared(VectorValues::Zero(y)); + this->backSubstitute(y, *x); + axpy(1.0, *xt_, *x); + return x; +} + +boost::tuple::shared_ptr> +SimpleSPCGSolver::splitGraph(const GaussianFactorGraph &gfg) { + + VariableIndex index(gfg); + size_t n = index.size(); + std::vector connected(n, false); + + GaussianFactorGraph::shared_ptr At(new GaussianFactorGraph()); + FactorGraph::shared_ptr Ac( new FactorGraph()); + + BOOST_FOREACH ( const GaussianFactor::shared_ptr &gf, gfg ) { + bool augment = false ; + + /* check whether this factor should be augmented to the "tree" graph */ + if ( gf->keys().size() == 1 ) augment = true; + else { + BOOST_FOREACH ( const Index key, *gf ) { + if ( connected[key] == false ) { + augment = true ; + } + connected[key] = true; + } + } + + if ( augment ) At->push_back(gf); + else Ac->push_back(boost::dynamic_pointer_cast(gf)); + } + +// gfg.print("gfg"); +// At->print("At"); +// Ac->print("Ac"); + + return boost::tie(At, Ac); +} + + + + + + +} diff --git a/gtsam/linear/SimpleSPCGSolver.h b/gtsam/linear/SimpleSPCGSolver.h new file mode 100644 index 000000000..04729fc1a --- /dev/null +++ b/gtsam/linear/SimpleSPCGSolver.h @@ -0,0 +1,91 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +#pragma once + +#include +#include +#include +#include + +namespace gtsam { + +/** + * This class gives a simple implementation to the SPCG solver presented in Dellaert et al in IROS'10. + * + * Given a linear least-squares problem \f$ f(x) = |A x - b|^2 \f$. We split the problem into + * \f$ f(x) = |A_t - b_t|^2 + |A_c - b_c|^2 \f$ where \f$ A_t \f$ denotes the "tree" part, and \f$ A_c \f$ denotes the "constraint" part. + * \f$ A_t \f$ is factorized into \f$ Q_t R_t \f$, and we compute \f$ c_t = Q_t^{-1} b_t \f$, and \f$ x_t = R_t^{-1} c_t \f$ accordingly. + * Then we solve a reparametrized problem \f$ f(y) = |y|^2 + |A_c R_t^{-1} y - \bar{b_y}|^2 \f$, where \f$ y = R_t(x - x_t) \f$, and \f$ \bar{b_y} = (b_c - A_c x_t) \f$ + * + * In the matrix form, it is equivalent to solving \f$ [A_c R_t^{-1} ; I ] y = [\bar{b_y} ; 0] \f$. We can solve it + * with the least-squares variation of the conjugate gradient method. + * + * Note: A full SPCG implementation will come up soon in the next release. + * + * \nosubgrouping + */ + +class SimpleSPCGSolver : public IterativeSolver { + +public: + + typedef IterativeSolver Base; + typedef boost::shared_ptr shared_ptr; + +protected: + + size_t nVar_ ; ///< number of variables \f$ x \f$ + size_t nAc_ ; ///< number of factors in \f$ A_c \f$ + FactorGraph::shared_ptr Ac_; ///< the constrained part of the graph + GaussianBayesNet::shared_ptr Rt_; ///< the gaussian bayes net of the tree part of the graph + VectorValues::shared_ptr xt_; ///< the solution of the \f$ A_t^{-1} b_t \f$ + VectorValues::shared_ptr y0_; ///< a column zero vector + VectorValues::shared_ptr by_; ///< \f$ [\bar{b_y} ; 0 ] \f$ + VectorValues::shared_ptr tmpY_; ///< buffer for the column vectors + VectorValues::shared_ptr tmpB_; ///< buffer for the row vectors + +public: + + SimpleSPCGSolver(const GaussianFactorGraph &gfg, const Parameters::shared_ptr ¶meters); + virtual ~SimpleSPCGSolver() {} + virtual VectorValues::shared_ptr optimize () {return optimize(*y0_);} + +protected: + + VectorValues::shared_ptr optimize (const VectorValues &initial); + + /** output = \f$ [\bar{b_y} ; 0 ] - [A_c R_t^{-1} ; I] \f$ input */ + void residual(const VectorValues &input, VectorValues &output); + + /** output = \f$ [A_c R_t^{-1} ; I] \f$ input */ + void multiply(const VectorValues &input, VectorValues &output); + + /** output = \f$ [R_t^{-T} A_c^T, I] \f$ input */ + void transposeMultiply(const VectorValues &input, VectorValues &output); + + /** output = \f$ R_t^{-1} \f$ input */ + void backSubstitute(const VectorValues &rhs, VectorValues &sol) ; + + /** output = \f$ R_t^{-T} \f$ input */ + void transposeBackSubstitute(const VectorValues &rhs, VectorValues &sol) ; + + /** return \f$ R_t^{-1} y + x_t \f$ */ + VectorValues::shared_ptr transform(const VectorValues &y); + + /** naively split a gaussian factor graph into tree and constraint parts + * Note: This function has to be refined for your graph/application */ + boost::tuple::shared_ptr> + splitGraph(const GaussianFactorGraph &gfg); + +}; + +} diff --git a/gtsam/nonlinear/ISAM2-impl.cpp b/gtsam/nonlinear/ISAM2-impl.cpp index e8847e5c0..05f42ad78 100644 --- a/gtsam/nonlinear/ISAM2-impl.cpp +++ b/gtsam/nonlinear/ISAM2-impl.cpp @@ -12,14 +12,16 @@ /** * @file ISAM2-impl.cpp * @brief Incremental update functionality (ISAM2) for BayesTree, with fluid relinearization. - * @author Michael Kaess, Richard Roberts + * @author Michael Kaess + * @author Richard Roberts */ +#include +#include // for selective linearization thresholds +#include #include #include #include -#include -#include namespace gtsam { diff --git a/gtsam/nonlinear/ISAM2.h b/gtsam/nonlinear/ISAM2.h index 42c38514c..0d5724865 100644 --- a/gtsam/nonlinear/ISAM2.h +++ b/gtsam/nonlinear/ISAM2.h @@ -94,8 +94,8 @@ struct ISAM2Params { * entries would be added with: * \code FastMap thresholds; - thresholds[PoseKey::chr()] = Vector_(6, 0.1, 0.1, 0.1, 0.5, 0.5, 0.5); // 0.1 rad rotation threshold, 0.5 m translation threshold - thresholds[PointKey::chr()] = Vector_(3, 1.0, 1.0, 1.0); // 1.0 m landmark position threshold + thresholds['x'] = Vector_(6, 0.1, 0.1, 0.1, 0.5, 0.5, 0.5); // 0.1 rad rotation threshold, 0.5 m translation threshold + thresholds['l'] = Vector_(3, 1.0, 1.0, 1.0); // 1.0 m landmark position threshold params.relinearizeThreshold = thresholds; \endcode */ diff --git a/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp b/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp index 3701511fe..042d4333d 100644 --- a/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp +++ b/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp @@ -23,6 +23,7 @@ #include // For NegativeMatrixException #include #include +#include using namespace std; @@ -73,7 +74,8 @@ void LevenbergMarquardtOptimizer::iterate() { delta = gtsam::optimize(*EliminationTree::Create(dampedSystem)->eliminate(params_.getEliminationFunction())); } else if ( params_.isCG() ) { - throw runtime_error("todo: "); + SimpleSPCGSolver solver(dampedSystem, *params_.iterativeParams); + delta = *solver.optimize(); } else { throw runtime_error("Optimization parameter is invalid: LevenbergMarquardtParams::elimination"); diff --git a/gtsam/nonlinear/NonlinearFactor.h b/gtsam/nonlinear/NonlinearFactor.h index bf6527599..73c150695 100644 --- a/gtsam/nonlinear/NonlinearFactor.h +++ b/gtsam/nonlinear/NonlinearFactor.h @@ -10,8 +10,8 @@ * -------------------------------------------------------------------------- */ /** - * @file NoiseModelFactor.h - * @brief Non-linear factor class + * @file NonlinearFactor.h + * @brief Non-linear factor base classes * @author Frank Dellaert * @author Richard Roberts */ @@ -33,7 +33,6 @@ #include #include -#include /** * Macro to add a standard clone function to a derived factor diff --git a/gtsam/nonlinear/Ordering.h b/gtsam/nonlinear/Ordering.h index 879b50677..f775f168b 100644 --- a/gtsam/nonlinear/Ordering.h +++ b/gtsam/nonlinear/Ordering.h @@ -17,14 +17,14 @@ #pragma once -#include -#include +#include #include -#include +#include #include #include #include +#include namespace gtsam { diff --git a/gtsam/nonlinear/SuccessiveLinearizationOptimizer.h b/gtsam/nonlinear/SuccessiveLinearizationOptimizer.h index 387a550db..ea54dd344 100644 --- a/gtsam/nonlinear/SuccessiveLinearizationOptimizer.h +++ b/gtsam/nonlinear/SuccessiveLinearizationOptimizer.h @@ -32,8 +32,7 @@ public: SEQUENTIAL_CHOLESKY, SEQUENTIAL_QR, CHOLMOD, /* Experimental Flag */ - PCG, /* Experimental Flag */ - LSPCG /* Experimental Flag */ + CG, /* Experimental Flag */ }; LinearSolverType linearSolverType; ///< The type of linear solver to use in the nonlinear optimizer @@ -62,11 +61,8 @@ public: case CHOLMOD: std::cout << " linear solver type: CHOLMOD\n"; break; - case PCG: - std::cout << " linear solver type: PCG\n"; - break; - case LSPCG: - std::cout << " linear solver type: LSPCG\n"; + case CG: + std::cout << " linear solver type: CG\n"; break; default: std::cout << " linear solver type: (invalid)\n"; @@ -94,16 +90,16 @@ public: } inline bool isCG() const { - return (linearSolverType == PCG || linearSolverType == LSPCG); + return (linearSolverType == CG); } GaussianFactorGraph::Eliminate getEliminationFunction() { switch (linearSolverType) { case MULTIFRONTAL_CHOLESKY: - case MULTIFRONTAL_QR: + case SEQUENTIAL_CHOLESKY: return EliminatePreferCholesky; - case SEQUENTIAL_CHOLESKY: + case MULTIFRONTAL_QR: case SEQUENTIAL_QR: return EliminateQR; diff --git a/gtsam/nonlinear/tests/testOrdering.cpp b/gtsam/nonlinear/tests/testOrdering.cpp index f57e3281a..beb16f741 100644 --- a/gtsam/nonlinear/tests/testOrdering.cpp +++ b/gtsam/nonlinear/tests/testOrdering.cpp @@ -14,9 +14,10 @@ * @author Alex Cunningham */ -#include -#include #include +#include +#include +#include using namespace std; using namespace gtsam; diff --git a/gtsam/nonlinear/tests/testSerializationNonlinear.cpp b/gtsam/nonlinear/tests/testSerializationNonlinear.cpp index 120a9fa94..bc023f115 100644 --- a/gtsam/nonlinear/tests/testSerializationNonlinear.cpp +++ b/gtsam/nonlinear/tests/testSerializationNonlinear.cpp @@ -16,11 +16,12 @@ * @date Feb 7, 2012 */ +#include +#include #include #include #include #include -#include #include #include diff --git a/gtsam/nonlinear/tests/testValues.cpp b/gtsam/nonlinear/tests/testValues.cpp index 6ccd3b083..3818e99a2 100644 --- a/gtsam/nonlinear/tests/testValues.cpp +++ b/gtsam/nonlinear/tests/testValues.cpp @@ -10,28 +10,33 @@ * -------------------------------------------------------------------------- */ /** - * @file testDynamicValues.cpp + * @file testValues.cpp * @author Richard Roberts */ -#include -#include -#include -#include // for operator += -using namespace boost::assign; - +#include +#include +#include +#include #include #include #include -#include -#include -#include + +#include +#include // for operator += +using namespace boost::assign; +#include +#include using namespace gtsam; using namespace std; static double inf = std::numeric_limits::infinity(); -const Key key1(Symbol('v',1)), key2(Symbol('v',2)), key3(Symbol('v',3)), key4(Symbol('v',4)); +// Convenience for named keys +using symbol_shorthand::X; +using symbol_shorthand::L; + +const Symbol key1('v',1), key2('v',2), key3('v',3), key4('v',4); /* ************************************************************************* */ TEST( Values, equals1 ) @@ -332,9 +337,9 @@ TEST(Values, Symbol_filter) { Pose3 pose3(Pose2(0.3, 0.7, 0.9)); Values values; - values.insert(Symbol('x',0), pose0); + values.insert(X(0), pose0); values.insert(Symbol('y',1), pose1); - values.insert(Symbol('x',2), pose2); + values.insert(X(2), pose2); values.insert(Symbol('y',3), pose3); int i = 0; diff --git a/gtsam/slam/BearingRangeFactor.h b/gtsam/slam/BearingRangeFactor.h index 9fe70123e..0bfa86540 100644 --- a/gtsam/slam/BearingRangeFactor.h +++ b/gtsam/slam/BearingRangeFactor.h @@ -66,7 +66,7 @@ namespace gtsam { << keyFormatter(this->key2()) << ")\n"; measuredBearing_.print(" measured bearing"); std::cout << " measured range: " << measuredRange_ << std::endl; - this->noiseModel_->print(" noise model"); + this->noiseModel_->print(" noise model: "); } /** equals */ diff --git a/gtsam/slam/BetweenFactor.h b/gtsam/slam/BetweenFactor.h index ec55c253b..62f66cc48 100644 --- a/gtsam/slam/BetweenFactor.h +++ b/gtsam/slam/BetweenFactor.h @@ -72,7 +72,7 @@ namespace gtsam { << keyFormatter(this->key1()) << "," << keyFormatter(this->key2()) << ")\n"; measured_.print(" measured"); - this->noiseModel_->print(" noise model"); + this->noiseModel_->print(" noise model: "); } /** equals */ diff --git a/gtsam/slam/GeneralSFMFactor.h b/gtsam/slam/GeneralSFMFactor.h index d046d0e1b..d64585b7d 100644 --- a/gtsam/slam/GeneralSFMFactor.h +++ b/gtsam/slam/GeneralSFMFactor.h @@ -20,9 +20,10 @@ #pragma once -#include #include - +#include +#include +#include namespace gtsam { diff --git a/gtsam/slam/PriorFactor.h b/gtsam/slam/PriorFactor.h index 6d958c652..608e717dd 100644 --- a/gtsam/slam/PriorFactor.h +++ b/gtsam/slam/PriorFactor.h @@ -64,7 +64,7 @@ namespace gtsam { virtual void print(const std::string& s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { std::cout << s << "PriorFactor(" << keyFormatter(this->key()) << ")\n"; prior_.print(" prior"); - this->noiseModel_->print(" noise model"); + this->noiseModel_->print(" noise model: "); } /** equals */ diff --git a/gtsam/slam/dataset.cpp b/gtsam/slam/dataset.cpp index f45f560a7..d4be33f31 100644 --- a/gtsam/slam/dataset.cpp +++ b/gtsam/slam/dataset.cpp @@ -16,7 +16,6 @@ * @brief utility functions for loading datasets */ - #include #include #include @@ -28,192 +27,219 @@ using namespace gtsam; #define LINESIZE 81920 -typedef boost::shared_ptr sharedPose2Graph; -typedef pose2SLAM::Odometry Pose2Factor; ///< Typedef for Constraint class for backwards compatibility - namespace gtsam { -/* ************************************************************************* */ -pair > dataset(const string& dataset, const string& user_path) { - string path = user_path, set = dataset; - boost::optional null_model; - boost::optional identity(noiseModel::Unit::Create(3)); - boost::optional small(noiseModel::Diagonal::Variances( - gtsam::Vector_(3, 0.0001, 0.0001, 0.0003))); + /* ************************************************************************* */ + pair > dataset(const string& dataset, + const string& user_path) { + string path = user_path, set = dataset; + boost::optional null_model; + boost::optional identity(noiseModel::Unit::Create(3)); + boost::optional small( + noiseModel::Diagonal::Variances( + gtsam::Vector_(3, 0.0001, 0.0001, 0.0003))); - if (path.empty()) path = string(getenv("HOME")) + "/data"; - if (set.empty()) set = string(getenv("DATASET")); + if (path.empty()) + path = string(getenv("HOME")) + "/data"; + if (set.empty()) + set = string(getenv("DATASET")); - if (set == "intel") return make_pair(path + "/Intel/intel.graph", null_model); - if (set == "intel-gfs") return make_pair(path + "/Intel/intel.gfs.graph", null_model); - if (set == "Killian-gfs") return make_pair(path + "/Killian/Killian.gfs.graph", null_model); - if (set == "Killian") return make_pair(path + "/Killian/Killian.graph", small); - if (set == "Killian-noised") return make_pair(path + "/Killian/Killian-noised.graph", null_model); - if (set == "3") return make_pair(path + "/TORO/w3-odom.graph", identity); - if (set == "100") return make_pair(path + "/TORO/w100-odom.graph", identity); - if (set == "10K") return make_pair(path + "/TORO/w10000-odom.graph", identity); - if (set == "10K2") return make_pair(path + "/hogman/data/2D/w10000.graph", - noiseModel::Diagonal::Variances(gtsam::Vector_(3, 0.1, 0.1, 0.05))); - if (set == "Eiffel100") return make_pair(path + "/TORO/w100-Eiffel.graph", identity); - if (set == "Eiffel10K") return make_pair(path + "/TORO/w10000-Eiffel.graph", identity); - if (set == "olson") return make_pair(path + "/Olson/olson06icra.graph", null_model); - if (set == "victoria") return make_pair(path + "/VictoriaPark/victoria_park.graph", null_model); - if (set == "beijing") return make_pair(path + "/Beijing/beijingData_trips.graph", null_model); + if (set == "intel") + return make_pair(path + "/Intel/intel.graph", null_model); + if (set == "intel-gfs") + return make_pair(path + "/Intel/intel.gfs.graph", null_model); + if (set == "Killian-gfs") + return make_pair(path + "/Killian/Killian.gfs.graph", null_model); + if (set == "Killian") + return make_pair(path + "/Killian/Killian.graph", small); + if (set == "Killian-noised") + return make_pair(path + "/Killian/Killian-noised.graph", null_model); + if (set == "3") + return make_pair(path + "/TORO/w3-odom.graph", identity); + if (set == "100") + return make_pair(path + "/TORO/w100-odom.graph", identity); + if (set == "10K") + return make_pair(path + "/TORO/w10000-odom.graph", identity); + if (set == "10K2") + return make_pair(path + "/hogman/data/2D/w10000.graph", + noiseModel::Diagonal::Variances(gtsam::Vector_(3, 0.1, 0.1, 0.05))); + if (set == "Eiffel100") + return make_pair(path + "/TORO/w100-Eiffel.graph", identity); + if (set == "Eiffel10K") + return make_pair(path + "/TORO/w10000-Eiffel.graph", identity); + if (set == "olson") + return make_pair(path + "/Olson/olson06icra.graph", null_model); + if (set == "victoria") + return make_pair(path + "/VictoriaPark/victoria_park.graph", null_model); + if (set == "beijing") + return make_pair(path + "/Beijing/beijingData_trips.graph", null_model); - return make_pair("unknown", null_model); -} - -/* ************************************************************************* */ - -pair load2D( - pair > dataset, - int maxID, bool addNoise, bool smart) { - return load2D(dataset.first, dataset.second, maxID, addNoise, smart); -} - -pair load2D(const string& filename, - boost::optional model, int maxID, bool addNoise, bool smart) { - cout << "Will try to read " << filename << endl; - ifstream is(filename.c_str()); - if (!is) { - cout << "load2D: can not find the file!"; - exit(-1); + return make_pair("unknown", null_model); } - Values::shared_ptr poses(new Values); - sharedPose2Graph graph(new pose2SLAM::Graph); + /* ************************************************************************* */ - string tag; + pair load2D( + pair > dataset, + int maxID, bool addNoise, bool smart) { + return load2D(dataset.first, dataset.second, maxID, addNoise, smart); + } - // load the poses - while (is) { - is >> tag; - - if ((tag == "VERTEX2") || (tag == "VERTEX")) { - int id; - double x, y, yaw; - is >> id >> x >> y >> yaw; - // optional filter - if (maxID && id >= maxID) continue; - poses->insert(pose2SLAM::PoseKey(id), Pose2(x, y, yaw)); + pair load2D( + const string& filename, boost::optional model, int maxID, + bool addNoise, bool smart) { + cout << "Will try to read " << filename << endl; + ifstream is(filename.c_str()); + if (!is) { + cout << "load2D: can not find the file!"; + exit(-1); } - is.ignore(LINESIZE, '\n'); - } - is.clear(); /* clears the end-of-file and error flags */ - is.seekg(0, ios::beg); - // load the factors - while (is) { - is >> tag; + pose2SLAM::Values::shared_ptr poses(new pose2SLAM::Values); + pose2SLAM::Graph::shared_ptr graph(new pose2SLAM::Graph); - if ((tag == "EDGE2") || (tag == "EDGE") || (tag == "ODOMETRY")) { - int id1, id2; - double x, y, yaw; + string tag; - is >> id1 >> id2 >> x >> y >> yaw; - Matrix m = eye(3); - is >> m(0, 0) >> m(0, 1) >> m(1, 1) >> m(2, 2) >> m(0, 2) >> m(1, 2); - m(2, 0) = m(0, 2); - m(2, 1) = m(1, 2); - m(1, 0) = m(0, 1); + // load the poses + while (is) { + is >> tag; - // optional filter - if (maxID && (id1 >= maxID || id2 >= maxID)) continue; - - Pose2 l1Xl2(x, y, yaw); - - // SharedNoiseModel noise = noiseModel::Gaussian::Covariance(m, smart); - if (!model) { - Vector variances = Vector_(3,m(0,0),m(1,1),m(2,2)); - model = noiseModel::Diagonal::Variances(variances, smart); + if ((tag == "VERTEX2") || (tag == "VERTEX")) { + int id; + double x, y, yaw; + is >> id >> x >> y >> yaw; + // optional filter + if (maxID && id >= maxID) + continue; + poses->insert(id, Pose2(x, y, yaw)); } - - if (addNoise) - l1Xl2 = l1Xl2.retract((*model)->sample()); - - // Insert vertices if pure odometry file - if (!poses->exists(pose2SLAM::PoseKey(id1))) poses->insert(pose2SLAM::PoseKey(id1), Pose2()); - if (!poses->exists(pose2SLAM::PoseKey(id2))) poses->insert(pose2SLAM::PoseKey(id2), poses->at(pose2SLAM::PoseKey(id1)) * l1Xl2); - - pose2SLAM::Graph::sharedFactor factor(new Pose2Factor(pose2SLAM::PoseKey(id1), pose2SLAM::PoseKey(id2), l1Xl2, *model)); - graph->push_back(factor); + is.ignore(LINESIZE, '\n'); } - is.ignore(LINESIZE, '\n'); - } + is.clear(); /* clears the end-of-file and error flags */ + is.seekg(0, ios::beg); - cout << "load2D read a graph file with " << poses->size() << " vertices and " - << graph->nrFactors() << " factors" << endl; + // load the factors + while (is) { + is >> tag; - return make_pair(graph, poses); -} + if ((tag == "EDGE2") || (tag == "EDGE") || (tag == "ODOMETRY")) { + int id1, id2; + double x, y, yaw; -/* ************************************************************************* */ -void save2D(const pose2SLAM::Graph& graph, const Values& config, const SharedDiagonal model, - const string& filename) { + is >> id1 >> id2 >> x >> y >> yaw; + Matrix m = eye(3); + is >> m(0, 0) >> m(0, 1) >> m(1, 1) >> m(2, 2) >> m(0, 2) >> m(1, 2); + m(2, 0) = m(0, 2); + m(2, 1) = m(1, 2); + m(1, 0) = m(0, 1); - fstream stream(filename.c_str(), fstream::out); + // optional filter + if (maxID && (id1 >= maxID || id2 >= maxID)) + continue; - // save poses - BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, config) { - const Pose2& pose = dynamic_cast(key_value.value); - stream << "VERTEX2 " << key_value.key << " " << pose.x() << " " << pose.y() << " " << pose.theta() << endl; - } + Pose2 l1Xl2(x, y, yaw); - // save edges - Matrix R = model->R(); - Matrix RR = trans(R)*R;//prod(trans(R),R); - BOOST_FOREACH(boost::shared_ptr factor_, graph) { - boost::shared_ptr factor = boost::dynamic_pointer_cast(factor_); - if (!factor) continue; + // SharedNoiseModel noise = noiseModel::Gaussian::Covariance(m, smart); + if (!model) { + Vector variances = Vector_(3, m(0, 0), m(1, 1), m(2, 2)); + model = noiseModel::Diagonal::Variances(variances, smart); + } - Pose2 pose = factor->measured().inverse(); - stream << "EDGE2 " << factor->key2() << " " << factor->key1() - << " " << pose.x() << " " << pose.y() << " " << pose.theta() - << " " << RR(0, 0) << " " << RR(0, 1) << " " << RR(1, 1) << " " << RR(2, 2) - << " " << RR(0, 2) << " " << RR(1, 2) << endl; - } + if (addNoise) + l1Xl2 = l1Xl2.retract((*model)->sample()); - stream.close(); -} + // Insert vertices if pure odometry file + if (!poses->exists(id1)) + poses->insert(id1, Pose2()); + if (!poses->exists(id2)) + poses->insert(id2, poses->at(id1) * l1Xl2); -/* ************************************************************************* */ -bool load3D(const string& filename) { - ifstream is(filename.c_str()); - if (!is) return false; - - while (is) { - char buf[LINESIZE]; - is.getline(buf, LINESIZE); - istringstream ls(buf); - string tag; - ls >> tag; - - if (tag == "VERTEX3") { - int id; - double x, y, z, roll, pitch, yaw; - ls >> id >> x >> y >> z >> roll >> pitch >> yaw; + pose2SLAM::Graph::sharedFactor factor( + new pose2SLAM::Odometry(id1, id2, l1Xl2, *model)); + graph->push_back(factor); + } + is.ignore(LINESIZE, '\n'); } + + cout << "load2D read a graph file with " << poses->size() + << " vertices and " << graph->nrFactors() << " factors" << endl; + + return make_pair(graph, poses); } - is.clear(); /* clears the end-of-file and error flags */ - is.seekg(0, ios::beg); - while (is) { - char buf[LINESIZE]; - is.getline(buf, LINESIZE); - istringstream ls(buf); - string tag; - ls >> tag; + /* ************************************************************************* */ + void save2D(const pose2SLAM::Graph& graph, const Values& config, + const SharedDiagonal model, const string& filename) { - if (tag == "EDGE3") { - int id1, id2; - double x, y, z, roll, pitch, yaw; - ls >> id1 >> id2 >> x >> y >> z >> roll >> pitch >> yaw; - Matrix m = eye(6); - for (int i = 0; i < 6; i++) - for (int j = i; j < 6; j++) - ls >> m(i, j); + fstream stream(filename.c_str(), fstream::out); + + // save poses + BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, config) + { + const Pose2& pose = dynamic_cast(key_value.value); + stream << "VERTEX2 " << key_value.key << " " << pose.x() << " " + << pose.y() << " " << pose.theta() << endl; + } + + // save edges + Matrix R = model->R(); + Matrix RR = trans(R) * R; //prod(trans(R),R); + BOOST_FOREACH(boost::shared_ptr factor_, graph) + { + boost::shared_ptr factor = + boost::dynamic_pointer_cast(factor_); + if (!factor) + continue; + + Pose2 pose = factor->measured().inverse(); + stream << "EDGE2 " << factor->key2() << " " << factor->key1() << " " + << pose.x() << " " << pose.y() << " " << pose.theta() << " " + << RR(0, 0) << " " << RR(0, 1) << " " << RR(1, 1) << " " + << RR(2, 2) << " " << RR(0, 2) << " " << RR(1, 2) << endl; + } + + stream.close(); + } + + /* ************************************************************************* */ + bool load3D(const string& filename) { + ifstream is(filename.c_str()); + if (!is) + return false; + + while (is) { + char buf[LINESIZE]; + is.getline(buf, LINESIZE); + istringstream ls(buf); + string tag; + ls >> tag; + + if (tag == "VERTEX3") { + int id; + double x, y, z, roll, pitch, yaw; + ls >> id >> x >> y >> z >> roll >> pitch >> yaw; + } } + is.clear(); /* clears the end-of-file and error flags */ + is.seekg(0, ios::beg); + + while (is) { + char buf[LINESIZE]; + is.getline(buf, LINESIZE); + istringstream ls(buf); + string tag; + ls >> tag; + + if (tag == "EDGE3") { + int id1, id2; + double x, y, z, roll, pitch, yaw; + ls >> id1 >> id2 >> x >> y >> z >> roll >> pitch >> yaw; + Matrix m = eye(6); + for (int i = 0; i < 6; i++) + for (int j = i; j < 6; j++) + ls >> m(i, j); + } + } + return true; } - return true; -} } diff --git a/gtsam/slam/dataset.h b/gtsam/slam/dataset.h index 5e06e583d..a099fb3d5 100644 --- a/gtsam/slam/dataset.h +++ b/gtsam/slam/dataset.h @@ -18,43 +18,52 @@ #pragma once - -#include #include +#include -namespace gtsam -{ -/** - * Construct dataset filename from short name - * Currently has "Killian" "intel.gfs", "10K", etc... - * @param filename - * @param optional dataset, if empty will try to getenv $DATASET - * @param optional path, if empty will try to getenv $HOME - */ -std::pair > +namespace gtsam { + /** + * Construct dataset filename from short name + * Currently has "Killian" "intel.gfs", "10K", etc... + * @param filename + * @param optional dataset, if empty will try to getenv $DATASET + * @param optional path, if empty will try to getenv $HOME + */ + std::pair > dataset(const std::string& dataset = "", const std::string& path = ""); -/** - * Load TORO 2D Graph - * @param filename - * @param maxID, if non-zero cut out vertices >= maxID - * @param smart: try to reduce complexity of covariance to cheapest model - */ -std::pair, boost::shared_ptr > load2D( - std::pair > dataset, - int maxID = 0, bool addNoise=false, bool smart=true); -std::pair, boost::shared_ptr > load2D( - const std::string& filename, - boost::optional model = boost::optional(), - int maxID = 0, bool addNoise=false, bool smart=true); + /** + * Load TORO 2D Graph + * @param dataset/model pair as constructed by [dataset] + * @param maxID if non-zero cut out vertices >= maxID + * @param addNoise add noise to the edges + * @param smart try to reduce complexity of covariance to cheapest model + */ + std::pair load2D( + std::pair > dataset, + int maxID = 0, bool addNoise = false, bool smart = true); -/** save 2d graph */ -void save2D(const pose2SLAM::Graph& graph, const Values& config, const gtsam::SharedDiagonal model, - const std::string& filename); + /** + * Load TORO 2D Graph + * @param filename + * @param model optional noise model to use instead of one specified by file + * @param maxID if non-zero cut out vertices >= maxID + * @param addNoise add noise to the edges + * @param smart try to reduce complexity of covariance to cheapest model + */ + std::pair load2D( + const std::string& filename, + boost::optional model = boost::optional< + gtsam::SharedDiagonal>(), int maxID = 0, bool addNoise = false, + bool smart = true); -/** - * Load TORO 3D Graph - */ -bool load3D(const std::string& filename); + /** save 2d graph */ + void save2D(const pose2SLAM::Graph& graph, const Values& config, + const gtsam::SharedDiagonal model, const std::string& filename); + + /** + * Load TORO 3D Graph + */ + bool load3D(const std::string& filename); } // namespace gtsam diff --git a/gtsam/slam/planarSLAM.cpp b/gtsam/slam/planarSLAM.cpp index b490a76cb..e385cb66f 100644 --- a/gtsam/slam/planarSLAM.cpp +++ b/gtsam/slam/planarSLAM.cpp @@ -26,39 +26,39 @@ namespace planarSLAM { NonlinearFactorGraph(graph) {} /* ************************************************************************* */ - void Graph::addPrior(Index i, const Pose2& p, const SharedNoiseModel& model) { - sharedFactor factor(new Prior(PoseKey(i), p, model)); + void Graph::addPrior(Key i, const Pose2& p, const SharedNoiseModel& model) { + sharedFactor factor(new Prior(i, p, model)); push_back(factor); } /* ************************************************************************* */ - void Graph::addPoseConstraint(Index i, const Pose2& p) { - sharedFactor factor(new Constraint(PoseKey(i), p)); + void Graph::addPoseConstraint(Key i, const Pose2& p) { + sharedFactor factor(new Constraint(i, p)); push_back(factor); } /* ************************************************************************* */ - void Graph::addOdometry(Index i, Index j, const Pose2& odometry, const SharedNoiseModel& model) { - sharedFactor factor(new Odometry(PoseKey(i), PoseKey(j), odometry, model)); + void Graph::addOdometry(Key i1, Key i2, const Pose2& odometry, const SharedNoiseModel& model) { + sharedFactor factor(new Odometry(i1, i2, odometry, model)); push_back(factor); } /* ************************************************************************* */ - void Graph::addBearing(Index i, Index j, const Rot2& z, const SharedNoiseModel& model) { - sharedFactor factor(new Bearing(PoseKey(i), PointKey(j), z, model)); + void Graph::addBearing(Key i, Key j, const Rot2& z, const SharedNoiseModel& model) { + sharedFactor factor(new Bearing(i, j, z, model)); push_back(factor); } /* ************************************************************************* */ - void Graph::addRange(Index i, Index j, double z, const SharedNoiseModel& model) { - sharedFactor factor(new Range(PoseKey(i), PointKey(j), z, model)); + void Graph::addRange(Key i, Key j, double z, const SharedNoiseModel& model) { + sharedFactor factor(new Range(i, j, z, model)); push_back(factor); } /* ************************************************************************* */ - void Graph::addBearingRange(Index i, Index j, const Rot2& z1, + void Graph::addBearingRange(Key i, Key j, const Rot2& z1, double z2, const SharedNoiseModel& model) { - sharedFactor factor(new BearingRange(PoseKey(i), PointKey(j), z1, z2, model)); + sharedFactor factor(new BearingRange(i, j, z1, z2, model)); push_back(factor); } diff --git a/gtsam/slam/planarSLAM.h b/gtsam/slam/planarSLAM.h index 818879f26..5d03cd646 100644 --- a/gtsam/slam/planarSLAM.h +++ b/gtsam/slam/planarSLAM.h @@ -11,7 +11,7 @@ /** * @file planarSLAM.h - * @brief: bearing/range measurements in 2D plane + * @brief bearing/range measurements in 2D plane * @author Frank Dellaert */ @@ -24,37 +24,38 @@ #include #include #include +#include #include +/** + * @defgroup SLAM + */ + // Use planarSLAM namespace for specific SLAM instance namespace planarSLAM { using namespace gtsam; - /// Convenience function for constructing a pose key - inline Symbol PoseKey(Index j) { return Symbol('x', j); } - - /// Convenience function for constructing a pose key - inline Symbol PointKey(Index j) { return Symbol('l', j); } - /* * List of typedefs for factors */ - /// A hard constraint for PoseKeys to enforce particular values + + /// A hard constraint for poses to enforce particular values typedef NonlinearEquality Constraint; - /// A prior factor to bias the value of a PoseKey + /// A prior factor to bias the value of a pose typedef PriorFactor Prior; - /// A factor between two PoseKeys set with a Pose2 + /// A factor between two poses set with a Pose2 typedef BetweenFactor Odometry; - /// A factor between a PoseKey and a PointKey to express difference in rotation (set with a Rot2) + /// A factor between a pose and a point to express difference in rotation (set with a Rot2) typedef BearingFactor Bearing; - /// A factor between a PoseKey and a PointKey to express distance between them (set with a double) + /// A factor between a pose and a point to express distance between them (set with a double) typedef RangeFactor Range; - /// A factor between a PoseKey and a PointKey to express difference in rotation and location + /// A factor between a pose and a point to express difference in rotation and location typedef BearingRangeFactor BearingRange; - /** Values class, using specific PoseKeys and PointKeys - * Mainly as a convenience for MATLAB wrapper, which does not allow for identically named methods + /* + * Values class, inherited from Values, mainly used as a convenience for MATLAB wrapper + * @ingroup SLAM */ struct Values: public gtsam::Values { @@ -67,19 +68,22 @@ namespace planarSLAM { } /// get a pose - Pose2 pose(Index key) const { return at(PoseKey(key)); } + Pose2 pose(Key i) const { return at(i); } /// get a point - Point2 point(Index key) const { return at(PointKey(key)); } + Point2 point(Key j) const { return at(j); } /// insert a pose - void insertPose(Index key, const Pose2& pose) { insert(PoseKey(key), pose); } + void insertPose(Key i, const Pose2& pose) { insert(i, pose); } /// insert a point - void insertPoint(Index key, const Point2& point) { insert(PointKey(key), point); } + void insertPoint(Key j, const Point2& point) { insert(j, point); } }; - /// Creates a NonlinearFactorGraph with the Values type + /** + * Graph class, inherited from NonlinearFactorGraph, used as a convenience for MATLAB wrapper + * @ingroup SLAM + */ struct Graph: public NonlinearFactorGraph { /// Default constructor for a NonlinearFactorGraph @@ -88,26 +92,31 @@ namespace planarSLAM { /// Creates a NonlinearFactorGraph based on another NonlinearFactorGraph Graph(const NonlinearFactorGraph& graph); - /// Biases the value of PoseKey key with Pose2 p given a noise model - void addPrior(Index poseKey, const Pose2& pose, const SharedNoiseModel& noiseModel); + /// Biases the value of pose key with Pose2 p given a noise model + void addPrior(Key i, const Pose2& pose, const SharedNoiseModel& noiseModel); - /// Creates a hard constraint to enforce Pose2 p for PoseKey poseKey's value - void addPoseConstraint(Index poseKey, const Pose2& pose); + /// Creates a hard constraint on the ith pose + void addPoseConstraint(Key i, const Pose2& pose); - /// Creates a factor with a Pose2 between PoseKeys poseKey and pointKey (poseKey.e. an odometry measurement) - void addOdometry(Index poseKey1, Index poseKey2, const Pose2& odometry, const SharedNoiseModel& model); + /// Creates an odometry factor between poses with keys i1 and i2 + void addOdometry(Key i1, Key i2, const Pose2& odometry, const SharedNoiseModel& model); - /// Creates a factor with a Rot2 between a PoseKey poseKey and PointKey pointKey for difference in rotation - void addBearing(Index poseKey, Index pointKey, const Rot2& bearing, const SharedNoiseModel& model); + /// Creates a bearing measurement from pose i to point j + void addBearing(Key i, Key j, const Rot2& bearing, const SharedNoiseModel& model); - /// Creates a factor with a Rot2 between a PoseKey poseKey and PointKey pointKey for difference in location - void addRange(Index poseKey, Index pointKey, double range, const SharedNoiseModel& model); + /// Creates a range measurement from pose i to point j + void addRange(Key i, Key k, double range, const SharedNoiseModel& model); - /// Creates a factor with a Rot2 between a PoseKey poseKey and PointKey pointKey for difference in rotation and location - void addBearingRange(Index poseKey, Index pointKey, const Rot2& bearing, double range, const SharedNoiseModel& model); + /// Creates a range/bearing measurement from pose i to point j + void addBearingRange(Key i, Key j, const Rot2& bearing, double range, const SharedNoiseModel& model); /// Optimize Values optimize(const Values& initialEstimate) const; + + /// Return a Marginals object + Marginals marginals(const Values& solution) const { + return Marginals(*this,solution); + } }; } // planarSLAM diff --git a/gtsam/slam/pose2SLAM.cpp b/gtsam/slam/pose2SLAM.cpp index 1a34904fc..49ab37111 100644 --- a/gtsam/slam/pose2SLAM.cpp +++ b/gtsam/slam/pose2SLAM.cpp @@ -23,31 +23,60 @@ namespace pose2SLAM { /* ************************************************************************* */ - Values circle(size_t n, double R) { + Values Values::Circle(size_t n, double R) { Values x; double theta = 0, dtheta = 2 * M_PI / n; for (size_t i = 0; i < n; i++, theta += dtheta) - x.insert(PoseKey(i), Pose2(cos(theta), sin(theta), (M_PI/2.0) + theta)); + x.insert(i, Pose2(cos(theta), sin(theta), M_PI_2 + theta)); return x; } /* ************************************************************************* */ - void Graph::addPrior(Index i, const Pose2& p, - const SharedNoiseModel& model) { - sharedFactor factor(new Prior(PoseKey(i), p, model)); + Vector Values::xs() const { + size_t j=0; + Vector result(size()); + ConstFiltered poses = filter(); + BOOST_FOREACH(const ConstFiltered::KeyValuePair& keyValue, poses) + result(j++) = keyValue.value.x(); + return result; + } + + /* ************************************************************************* */ + Vector Values::ys() const { + size_t j=0; + Vector result(size()); + ConstFiltered poses = filter(); + BOOST_FOREACH(const ConstFiltered::KeyValuePair& keyValue, poses) + result(j++) = keyValue.value.y(); + return result; + } + + /* ************************************************************************* */ + Vector Values::thetas() const { + size_t j=0; + Vector result(size()); + ConstFiltered poses = filter(); + BOOST_FOREACH(const ConstFiltered::KeyValuePair& keyValue, poses) + result(j++) = keyValue.value.theta (); + return result; + } + + /* ************************************************************************* */ + void Graph::addPrior(Key i, const Pose2& p, const SharedNoiseModel& model) { + sharedFactor factor(new Prior(i, p, model)); push_back(factor); } /* ************************************************************************* */ - void Graph::addPoseConstraint(Index i, const Pose2& p) { - sharedFactor factor(new HardConstraint(PoseKey(i), p)); + void Graph::addPoseConstraint(Key i, const Pose2& p) { + sharedFactor factor(new HardConstraint(i, p)); push_back(factor); } /* ************************************************************************* */ - void Graph::addOdometry(Index i, Index j, const Pose2& z, + void Graph::addOdometry(Key i1, Key i2, const Pose2& z, const SharedNoiseModel& model) { - sharedFactor factor(new Odometry(PoseKey(i), PoseKey(j), z, model)); + sharedFactor factor(new Odometry(i1, i2, z, model)); push_back(factor); } diff --git a/gtsam/slam/pose2SLAM.h b/gtsam/slam/pose2SLAM.h index 50944cf2f..d7ebd3323 100644 --- a/gtsam/slam/pose2SLAM.h +++ b/gtsam/slam/pose2SLAM.h @@ -19,7 +19,6 @@ #include #include -#include #include #include #include @@ -31,13 +30,15 @@ namespace pose2SLAM { using namespace gtsam; - /// Convenience function for constructing a pose key - inline Symbol PoseKey(Index j) { return Symbol('x', j); } - - /// Values class, inherited from Values, using PoseKeys, mainly used as a convenience for MATLAB wrapper + /* + * Values class, inherited from Values, mainly used as a convenience for MATLAB wrapper + * @ingroup SLAM + */ struct Values: public gtsam::Values { - /// Default constructor + typedef boost::shared_ptr shared_ptr; + + /// Default constructor Values() {} /// Copy constructor @@ -45,23 +46,25 @@ namespace pose2SLAM { gtsam::Values(values) { } - // Convenience for MATLAB wrapper, which does not allow for identically named methods - - /// get a pose - Pose2 pose(Index key) const { return at(PoseKey(key)); } + /** + * Create a circle of n 2D poses tangent to circle of radius R, first pose at (R,0) + * @param n number of poses + * @param R radius of circle + * @param c character to use for keys + * @return circle of n 2D poses + */ + static Values Circle(size_t n, double R); /// insert a pose - void insertPose(Index key, const Pose2& pose) { insert(PoseKey(key), pose); } - }; + void insertPose(Key i, const Pose2& pose) { insert(i, pose); } - /** - * Create a circle of n 2D poses tangent to circle of radius R, first pose at (R,0) - * @param n number of poses - * @param R radius of circle - * @param c character to use for keys - * @return circle of n 2D poses - */ - Values circle(size_t n, double R); + /// get a pose + Pose2 pose(Key i) const { return at(i); } + + Vector xs() const; ///< get all x coordinates in a matrix + Vector ys() const; ///< get all y coordinates in a matrix + Vector thetas() const; ///< get all orientations in a matrix + }; /** * List of typedefs for factors @@ -74,29 +77,32 @@ namespace pose2SLAM { /// A factor to add an odometry measurement between two poses. typedef BetweenFactor Odometry; - /// Graph + /** + * Graph class, inherited from NonlinearFactorGraph, used as a convenience for MATLAB wrapper + * @ingroup SLAM + */ struct Graph: public NonlinearFactorGraph { - /// Default constructor for a NonlinearFactorGraph + typedef boost::shared_ptr shared_ptr; + + /// Default constructor for a NonlinearFactorGraph Graph(){} /// Creates a NonlinearFactorGraph based on another NonlinearFactorGraph Graph(const NonlinearFactorGraph& graph); - /// Adds a Pose2 prior with a noise model to one of the keys in the nonlinear factor graph - void addPrior(Index i, const Pose2& p, const SharedNoiseModel& model); + /// Adds a Pose2 prior with mean p and given noise model on pose i + void addPrior(Key i, const Pose2& p, const SharedNoiseModel& model); /// Creates a hard constraint for key i with the given Pose2 p. - void addPoseConstraint(Index i, const Pose2& p); + void addPoseConstraint(Key i, const Pose2& p); - /// Creates a between factor between keys i and j with a noise model with Pose2 z in the graph - void addOdometry(Index i, Index j, const Pose2& z, - const SharedNoiseModel& model); + /// Creates an odometry factor between poses with keys i1 and i2 + void addOdometry(Key i1, Key i2, const Pose2& z, const SharedNoiseModel& model); /// AddConstraint adds a soft constraint between factor between keys i and j - void addConstraint(Index i, Index j, const Pose2& z, - const SharedNoiseModel& model) { - addOdometry(i,j,z,model); // same for now + void addConstraint(Key i1, Key i2, const Pose2& z, const SharedNoiseModel& model) { + addOdometry(i1,i2,z,model); // same for now } /// Optimize diff --git a/gtsam/slam/pose3SLAM.cpp b/gtsam/slam/pose3SLAM.cpp index 0ab962f1e..c7f8a29c5 100644 --- a/gtsam/slam/pose3SLAM.cpp +++ b/gtsam/slam/pose3SLAM.cpp @@ -22,7 +22,7 @@ namespace pose3SLAM { /* ************************************************************************* */ - Values circle(size_t n, double radius) { + Values Values::Circle(size_t n, double radius) { Values x; double theta = 0, dtheta = 2 * M_PI / n; // We use aerospace/navlab convention, X forward, Y right, Z down @@ -36,26 +36,56 @@ namespace pose3SLAM { Point3 gti(radius*cos(theta), radius*sin(theta), 0); Rot3 _0Ri = Rot3::yaw(-theta); // negative yaw goes counterclockwise, with Z down ! Pose3 gTi(gR0 * _0Ri, gti); - x.insert(PoseKey(i), gTi); + x.insert(i, gTi); } return x; } /* ************************************************************************* */ - void Graph::addPrior(Index i, const Pose3& p, const SharedNoiseModel& model) { - sharedFactor factor(new Prior(PoseKey(i), p, model)); + Vector Values::xs() const { + size_t j=0; + Vector result(size()); + ConstFiltered poses = filter(); + BOOST_FOREACH(const ConstFiltered::KeyValuePair& keyValue, poses) + result(j++) = keyValue.value.x(); + return result; + } + + /* ************************************************************************* */ + Vector Values::ys() const { + size_t j=0; + Vector result(size()); + ConstFiltered poses = filter(); + BOOST_FOREACH(const ConstFiltered::KeyValuePair& keyValue, poses) + result(j++) = keyValue.value.y(); + return result; + } + + /* ************************************************************************* */ + Vector Values::zs() const { + size_t j=0; + Vector result(size()); + ConstFiltered poses = filter(); + BOOST_FOREACH(const ConstFiltered::KeyValuePair& keyValue, poses) + result(j++) = keyValue.value.z(); + return result; + } + + /* ************************************************************************* */ + void Graph::addPrior(Key i, const Pose3& p, const SharedNoiseModel& model) { + sharedFactor factor(new Prior(i, p, model)); push_back(factor); } /* ************************************************************************* */ - void Graph::addConstraint(Index i, Index j, const Pose3& z, const SharedNoiseModel& model) { - sharedFactor factor(new Constraint(PoseKey(i), PoseKey(j), z, model)); + void Graph::addConstraint(Key i1, Key i2, const Pose3& z, const SharedNoiseModel& model) { + sharedFactor factor(new Constraint(i1, i2, z, model)); push_back(factor); } /* ************************************************************************* */ - void Graph::addHardConstraint(Index i, const Pose3& p) { - sharedFactor factor(new HardConstraint(PoseKey(i), p)); + void Graph::addHardConstraint(Key i, const Pose3& p) { + sharedFactor factor(new HardConstraint(i, p)); push_back(factor); } diff --git a/gtsam/slam/pose3SLAM.h b/gtsam/slam/pose3SLAM.h index 6b4efbe6c..448914f0d 100644 --- a/gtsam/slam/pose3SLAM.h +++ b/gtsam/slam/pose3SLAM.h @@ -17,29 +17,53 @@ #pragma once -#include #include #include -#include #include #include #include +#include +#include /// Use pose3SLAM namespace for specific SLAM instance namespace pose3SLAM { using namespace gtsam; - /// Convenience function for constructing a pose key - inline Symbol PoseKey(Index j) { return Symbol('x', j); } - - /** - * Create a circle of n 3D poses tangent to circle of radius R, first pose at (R,0) - * @param n number of poses - * @param R radius of circle - * @return circle of n 3D poses + /* + * Values class, inherited from Values, mainly used as a convenience for MATLAB wrapper + * @ingroup SLAM */ - Values circle(size_t n, double R); + struct Values: public gtsam::Values { + + typedef boost::shared_ptr shared_ptr; + + /// Default constructor + Values() {} + + /// Copy constructor + Values(const gtsam::Values& values) : + gtsam::Values(values) { + } + + /** + * Create a circle of n 3D poses tangent to circle of radius R, first pose at (R,0) + * @param n number of poses + * @param R radius of circle + * @return circle of n 3D poses + */ + static Values Circle(size_t n, double R); + + /// insert a pose + void insertPose(Key i, const Pose3& pose) { insert(i, pose); } + + /// get a pose + Pose3 pose(Key i) const { return at(i); } + + Vector xs() const; ///< get all x coordinates in a matrix + Vector ys() const; ///< get all y coordinates in a matrix + Vector zs() const; ///< get all z coordinates in a matrix + }; /// A prior factor on Key with Pose3 data type. typedef PriorFactor Prior; @@ -48,23 +72,30 @@ namespace pose3SLAM { /// A hard constraint would enforce that the given key would have the input value in the results. typedef NonlinearEquality HardConstraint; - /// Graph + /** + * Graph class, inherited from NonlinearFactorGraph, used as a convenience for MATLAB wrapper + * @ingroup SLAM + */ struct Graph: public NonlinearFactorGraph { /// Adds a factor between keys of the same type - void addPrior(Index i, const Pose3& p, const SharedNoiseModel& model); + void addPrior(Key i, const Pose3& p, const SharedNoiseModel& model); /// Creates a between factor between keys i and j with a noise model with Pos3 z in the graph - void addConstraint(Index i, Index j, const Pose3& z, const SharedNoiseModel& model); + void addConstraint(Key i1, Key i2, const Pose3& z, const SharedNoiseModel& model); /// Creates a hard constraint for key i with the given Pose3 p. - void addHardConstraint(Index i, const Pose3& p); + void addHardConstraint(Key i, const Pose3& p); /// Optimize Values optimize(const Values& initialEstimate) { return LevenbergMarquardtOptimizer(*this, initialEstimate).optimize(); } + /// Return a Marginals object + Marginals marginals(const Values& solution) const { + return Marginals(*this,solution); + } }; } // pose3SLAM diff --git a/gtsam/slam/simulated2D.h b/gtsam/slam/simulated2D.h index e9b4f2bc9..403fac109 100644 --- a/gtsam/slam/simulated2D.h +++ b/gtsam/slam/simulated2D.h @@ -30,12 +30,6 @@ namespace simulated2D { // Simulated2D robots have no orientation, just a position - /// Convenience function for constructing a pose key - inline Symbol PoseKey(Index j) { return Symbol('x', j); } - - /// Convenience function for constructing a landmark key - inline Symbol PointKey(Index j) { return Symbol('l', j); } - /** * Custom Values class that holds poses and points, mainly used as a convenience for MATLAB wrapper */ @@ -57,14 +51,14 @@ namespace simulated2D { } /// Insert a pose - void insertPose(Index j, const Point2& p) { - insert(PoseKey(j), p); + void insertPose(Key i, const Point2& p) { + insert(i, p); nrPoses_++; } /// Insert a point - void insertPoint(Index j, const Point2& p) { - insert(PointKey(j), p); + void insertPoint(Key j, const Point2& p) { + insert(j, p); nrPoints_++; } @@ -79,13 +73,13 @@ namespace simulated2D { } /// Return pose i - Point2 pose(Index j) const { - return at(PoseKey(j)); + Point2 pose(Key i) const { + return at(i); } /// Return point j - Point2 point(Index j) const { - return at(PointKey(j)); + Point2 point(Key j) const { + return at(j); } }; @@ -171,8 +165,8 @@ namespace simulated2D { Pose measured_; ///< odometry measurement /// Create odometry - GenericOdometry(const Pose& measured, const SharedNoiseModel& model, Key key1, Key key2) : - Base(model, key1, key2), measured_(measured) { + GenericOdometry(const Pose& measured, const SharedNoiseModel& model, Key i1, Key i2) : + Base(model, i1, i2), measured_(measured) { } /// Evaluate error and optionally return derivatives @@ -215,8 +209,8 @@ namespace simulated2D { Landmark measured_; ///< Measurement /// Create measurement factor - GenericMeasurement(const Landmark& measured, const SharedNoiseModel& model, Key poseKey, Key landmarkKey) : - Base(model, poseKey, landmarkKey), measured_(measured) { + GenericMeasurement(const Landmark& measured, const SharedNoiseModel& model, Key i, Key j) : + Base(model, i, j), measured_(measured) { } /// Evaluate error and optionally return derivatives diff --git a/gtsam/slam/simulated2DOriented.h b/gtsam/slam/simulated2DOriented.h index c7ebd466c..ed0d8ba1a 100644 --- a/gtsam/slam/simulated2DOriented.h +++ b/gtsam/slam/simulated2DOriented.h @@ -19,6 +19,7 @@ #pragma once #include +#include #include #include @@ -27,12 +28,6 @@ namespace simulated2DOriented { using namespace gtsam; - /// Convenience function for constructing a pose key - inline Symbol PoseKey(Index j) { return Symbol('x', j); } - - /// Convenience function for constructing a landmark key - inline Symbol PointKey(Index j) { return Symbol('l', j); } - /// Specialized Values structure with syntactic sugar for /// compatibility with matlab class Values: public gtsam::Values { @@ -40,21 +35,23 @@ namespace simulated2DOriented { public: Values() : nrPoses_(0), nrPoints_(0) {} - void insertPose(Index j, const Pose2& p) { - insert(PoseKey(j), p); + /// insert a pose + void insertPose(Key i, const Pose2& p) { + insert(i, p); nrPoses_++; } - void insertPoint(Index j, const Point2& p) { - insert(PointKey(j), p); + /// insert a landmark + void insertPoint(Key j, const Point2& p) { + insert(j, p); nrPoints_++; } - int nrPoses() const { return nrPoses_; } - int nrPoints() const { return nrPoints_; } + int nrPoses() const { return nrPoses_; } ///< nr of poses + int nrPoints() const { return nrPoints_; } ///< nr of landmarks - Pose2 pose(Index j) const { return at(PoseKey(j)); } - Point2 point(Index j) const { return at(PointKey(j)); } + Pose2 pose(Key i) const { return at(i); } ///< get a pose + Point2 point(Key j) const { return at(j); } ///< get a landmark }; //TODO:: point prior is not implemented right now diff --git a/gtsam/slam/smallExample.cpp b/gtsam/slam/smallExample.cpp index fae2d2e22..5b0ee90dd 100644 --- a/gtsam/slam/smallExample.cpp +++ b/gtsam/slam/smallExample.cpp @@ -17,28 +17,25 @@ * @author Frank dellaert */ -#include -#include +#include +#include +#include +#include +#include +#include +#include + #include #include +#include +#include + using namespace std; -#include -#include -#include - -// template definitions -#include -#include -#include - namespace gtsam { namespace example { - using simulated2D::PoseKey; - using simulated2D::PointKey; - typedef boost::shared_ptr shared; static SharedDiagonal sigma1_0 = noiseModel::Isotropic::Sigma(2,1.0); @@ -49,8 +46,9 @@ namespace example { static const Index _l1_=0, _x1_=1, _x2_=2; static const Index _x_=0, _y_=1, _z_=2; - Key kx(size_t i) { return Symbol('x',i); } - Key kl(size_t i) { return Symbol('l',i); } + // Convenience for named keys + using symbol_shorthand::X; + using symbol_shorthand::L; /* ************************************************************************* */ boost::shared_ptr sharedNonlinearFactorGraph() { @@ -60,22 +58,22 @@ namespace example { // prior on x1 Point2 mu; - shared f1(new simulated2D::Prior(mu, sigma0_1, PoseKey(1))); + shared f1(new simulated2D::Prior(mu, sigma0_1, X(1))); nlfg->push_back(f1); // odometry between x1 and x2 Point2 z2(1.5, 0); - shared f2(new simulated2D::Odometry(z2, sigma0_1, PoseKey(1), PoseKey(2))); + shared f2(new simulated2D::Odometry(z2, sigma0_1, X(1), X(2))); nlfg->push_back(f2); // measurement between x1 and l1 Point2 z3(0, -1); - shared f3(new simulated2D::Measurement(z3, sigma0_2, PoseKey(1), PointKey(1))); + shared f3(new simulated2D::Measurement(z3, sigma0_2, X(1), L(1))); nlfg->push_back(f3); // measurement between x2 and l1 Point2 z4(-1.5, -1.); - shared f4(new simulated2D::Measurement(z4, sigma0_2, PoseKey(2), PointKey(1))); + shared f4(new simulated2D::Measurement(z4, sigma0_2, X(2), L(1))); nlfg->push_back(f4); return nlfg; @@ -89,9 +87,9 @@ namespace example { /* ************************************************************************* */ Values createValues() { Values c; - c.insert(PoseKey(1), Point2(0.0, 0.0)); - c.insert(PoseKey(2), Point2(1.5, 0.0)); - c.insert(PointKey(1), Point2(0.0, -1.0)); + c.insert(X(1), Point2(0.0, 0.0)); + c.insert(X(2), Point2(1.5, 0.0)); + c.insert(L(1), Point2(0.0, -1.0)); return c; } @@ -107,9 +105,9 @@ namespace example { /* ************************************************************************* */ boost::shared_ptr sharedNoisyValues() { boost::shared_ptr c(new Values); - c->insert(PoseKey(1), Point2(0.1, 0.1)); - c->insert(PoseKey(2), Point2(1.4, 0.2)); - c->insert(PointKey(1), Point2(0.1, -1.1)); + c->insert(X(1), Point2(0.1, 0.1)); + c->insert(X(2), Point2(1.4, 0.2)); + c->insert(L(1), Point2(0.1, -1.1)); return c; } @@ -121,18 +119,18 @@ namespace example { /* ************************************************************************* */ VectorValues createCorrectDelta(const Ordering& ordering) { VectorValues c(vector(3,2)); - c[ordering[kl(1)]] = Vector_(2, -0.1, 0.1); - c[ordering[kx(1)]] = Vector_(2, -0.1, -0.1); - c[ordering[kx(2)]] = Vector_(2, 0.1, -0.2); + c[ordering[L(1)]] = Vector_(2, -0.1, 0.1); + c[ordering[X(1)]] = Vector_(2, -0.1, -0.1); + c[ordering[X(2)]] = Vector_(2, 0.1, -0.2); return c; } /* ************************************************************************* */ VectorValues createZeroDelta(const Ordering& ordering) { VectorValues c(vector(3,2)); - c[ordering[kl(1)]] = zero(2); - c[ordering[kx(1)]] = zero(2); - c[ordering[kx(2)]] = zero(2); + c[ordering[L(1)]] = zero(2); + c[ordering[X(1)]] = zero(2); + c[ordering[X(2)]] = zero(2); return c; } @@ -144,16 +142,16 @@ namespace example { SharedDiagonal unit2 = noiseModel::Unit::Create(2); // linearized prior on x1: c[_x1_]+x1=0 i.e. x1=-c[_x1_] - fg.add(ordering[kx(1)], 10*eye(2), -1.0*ones(2), unit2); + fg.add(ordering[X(1)], 10*eye(2), -1.0*ones(2), unit2); // odometry between x1 and x2: x2-x1=[0.2;-0.1] - fg.add(ordering[kx(1)], -10*eye(2),ordering[kx(2)], 10*eye(2), Vector_(2, 2.0, -1.0), unit2); + fg.add(ordering[X(1)], -10*eye(2),ordering[X(2)], 10*eye(2), Vector_(2, 2.0, -1.0), unit2); // measurement between x1 and l1: l1-x1=[0.0;0.2] - fg.add(ordering[kx(1)], -5*eye(2), ordering[kl(1)], 5*eye(2), Vector_(2, 0.0, 1.0), unit2); + fg.add(ordering[X(1)], -5*eye(2), ordering[L(1)], 5*eye(2), Vector_(2, 0.0, 1.0), unit2); // measurement between x2 and l1: l1-x2=[-0.2;0.3] - fg.add(ordering[kx(2)], -5*eye(2), ordering[kl(1)], 5*eye(2), Vector_(2, -1.0, 1.5), unit2); + fg.add(ordering[X(2)], -5*eye(2), ordering[L(1)], 5*eye(2), Vector_(2, -1.0, 1.5), unit2); return *fg.dynamicCastFactors >(); } @@ -223,7 +221,7 @@ namespace example { Vector z = Vector_(2, 1.0, 0.0); double sigma = 0.1; boost::shared_ptr factor( - new smallOptimize::UnaryFactor(z, noiseModel::Isotropic::Sigma(2,sigma), PoseKey(1))); + new smallOptimize::UnaryFactor(z, noiseModel::Isotropic::Sigma(2,sigma), X(1))); fg->push_back(factor); return fg; } @@ -241,23 +239,23 @@ namespace example { // prior on x1 Point2 x1(1.0, 0.0); - shared prior(new simulated2D::Prior(x1, sigma1_0, PoseKey(1))); + shared prior(new simulated2D::Prior(x1, sigma1_0, X(1))); nlfg.push_back(prior); - poses.insert(simulated2D::PoseKey(1), x1); + poses.insert(X(1), x1); for (int t = 2; t <= T; t++) { // odometry between x_t and x_{t-1} Point2 odo(1.0, 0.0); - shared odometry(new simulated2D::Odometry(odo, sigma1_0, PoseKey(t - 1), PoseKey(t))); + shared odometry(new simulated2D::Odometry(odo, sigma1_0, X(t - 1), X(t))); nlfg.push_back(odometry); // measurement on x_t is like perfect GPS Point2 xt(t, 0); - shared measurement(new simulated2D::Prior(xt, sigma1_0, PoseKey(t))); + shared measurement(new simulated2D::Prior(xt, sigma1_0, X(t))); nlfg.push_back(measurement); // initial estimate - poses.insert(PoseKey(t), xt); + poses.insert(X(t), xt); } return make_pair(nlfg, poses); @@ -418,7 +416,7 @@ namespace example { /* ************************************************************************* */ // Create key for simulated planar graph Symbol key(int x, int y) { - return PoseKey(1000*x+y); + return X(1000*x+y); } /* ************************************************************************* */ diff --git a/gtsam/slam/tests/testAntiFactor.cpp b/gtsam/slam/tests/testAntiFactor.cpp index 183b0c600..b73118352 100644 --- a/gtsam/slam/tests/testAntiFactor.cpp +++ b/gtsam/slam/tests/testAntiFactor.cpp @@ -27,8 +27,6 @@ using namespace std; using namespace gtsam; -using pose3SLAM::PoseKey; - /* ************************************************************************* */ TEST( AntiFactor, NegativeHessian) { @@ -42,17 +40,17 @@ TEST( AntiFactor, NegativeHessian) // Create a configuration corresponding to the ground truth boost::shared_ptr values(new Values()); - values->insert(PoseKey(1), pose1); - values->insert(PoseKey(2), pose2); + values->insert(1, pose1); + values->insert(2, pose2); // Define an elimination ordering Ordering::shared_ptr ordering(new Ordering()); - ordering->insert(PoseKey(1), 0); - ordering->insert(PoseKey(2), 1); + ordering->insert(1, 0); + ordering->insert(2, 1); // Create a "standard" factor - BetweenFactor::shared_ptr originalFactor(new BetweenFactor(PoseKey(1), PoseKey(2), z, sigma)); + BetweenFactor::shared_ptr originalFactor(new BetweenFactor(1, 2, z, sigma)); // Linearize it into a Jacobian Factor GaussianFactor::shared_ptr originalJacobian = originalFactor->linearize(*values, *ordering); @@ -103,8 +101,8 @@ TEST( AntiFactor, EquivalentBayesNet) // Create a configuration corresponding to the ground truth boost::shared_ptr values(new Values()); - values->insert(PoseKey(1), pose1); - values->insert(PoseKey(2), pose2); + values->insert(1, pose1); + values->insert(2, pose2); // Define an elimination ordering Ordering::shared_ptr ordering = graph->orderingCOLAMD(*values); @@ -117,7 +115,7 @@ TEST( AntiFactor, EquivalentBayesNet) VectorValues expectedDeltas = optimize(*expectedBayesNet); // Add an additional factor between Pose1 and Pose2 - pose3SLAM::Constraint::shared_ptr f1(new pose3SLAM::Constraint(PoseKey(1), PoseKey(2), z, sigma)); + pose3SLAM::Constraint::shared_ptr f1(new pose3SLAM::Constraint(1, 2, z, sigma)); graph->push_back(f1); // Add the corresponding AntiFactor between Pose1 and Pose2 diff --git a/gtsam/slam/tests/testGeneralSFMFactor.cpp b/gtsam/slam/tests/testGeneralSFMFactor.cpp index 341549309..1306f5148 100644 --- a/gtsam/slam/tests/testGeneralSFMFactor.cpp +++ b/gtsam/slam/tests/testGeneralSFMFactor.cpp @@ -16,27 +16,32 @@ * @brief unit tests for GeneralSFMFactor */ -#include -#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include #include #include using namespace boost; -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include +#include +#include using namespace std; using namespace gtsam; +// Convenience for named keys +using symbol_shorthand::X; +using symbol_shorthand::L; + typedef PinholeCamera GeneralCamera; typedef GeneralSFMFactor Projection; typedef NonlinearEquality CameraConstraint; @@ -45,16 +50,16 @@ typedef NonlinearEquality Point3Constraint; class Graph: public NonlinearFactorGraph { public: void addMeasurement(int i, int j, const Point2& z, const SharedNoiseModel& model) { - push_back(boost::make_shared(z, model, Symbol('x',i), Symbol('l',j))); + push_back(boost::make_shared(z, model, X(i), L(j))); } void addCameraConstraint(int j, const GeneralCamera& p) { - boost::shared_ptr factor(new CameraConstraint(Symbol('x',j), p)); + boost::shared_ptr factor(new CameraConstraint(X(j), p)); push_back(factor); } void addPoint3Constraint(int j, const Point3& p) { - boost::shared_ptr factor(new Point3Constraint(Symbol('l',j), p)); + boost::shared_ptr factor(new Point3Constraint(L(j), p)); push_back(factor); } @@ -97,14 +102,14 @@ TEST( GeneralSFMFactor, equals ) TEST( GeneralSFMFactor, error ) { Point2 z(3.,0.); const SharedNoiseModel sigma(noiseModel::Unit::Create(1)); - boost::shared_ptr factor(new Projection(z, sigma, Symbol('x',1), Symbol('l',1))); + boost::shared_ptr factor(new Projection(z, sigma, X(1), L(1))); // For the following configuration, the factor predicts 320,240 Values values; Rot3 R; Point3 t1(0,0,-6); Pose3 x1(R,t1); - values.insert(Symbol('x',1), GeneralCamera(x1)); - Point3 l1; values.insert(Symbol('l',1), l1); + values.insert(X(1), GeneralCamera(x1)); + Point3 l1; values.insert(L(1), l1); EXPECT(assert_equal(Vector_(2, -3.0, 0.0), factor->unwhitenedError(values))); } @@ -113,20 +118,20 @@ static const double baseline = 5.0 ; /* ************************************************************************* */ vector genPoint3() { const double z = 5; - vector L ; - L.push_back(Point3 (-1.0,-1.0, z)); - L.push_back(Point3 (-1.0, 1.0, z)); - L.push_back(Point3 ( 1.0, 1.0, z)); - L.push_back(Point3 ( 1.0,-1.0, z)); - L.push_back(Point3 (-1.5,-1.5, 1.5*z)); - L.push_back(Point3 (-1.5, 1.5, 1.5*z)); - L.push_back(Point3 ( 1.5, 1.5, 1.5*z)); - L.push_back(Point3 ( 1.5,-1.5, 1.5*z)); - L.push_back(Point3 (-2.0,-2.0, 2*z)); - L.push_back(Point3 (-2.0, 2.0, 2*z)); - L.push_back(Point3 ( 2.0, 2.0, 2*z)); - L.push_back(Point3 ( 2.0,-2.0, 2*z)); - return L ; + vector landmarks ; + landmarks.push_back(Point3 (-1.0,-1.0, z)); + landmarks.push_back(Point3 (-1.0, 1.0, z)); + landmarks.push_back(Point3 ( 1.0, 1.0, z)); + landmarks.push_back(Point3 ( 1.0,-1.0, z)); + landmarks.push_back(Point3 (-1.5,-1.5, 1.5*z)); + landmarks.push_back(Point3 (-1.5, 1.5, 1.5*z)); + landmarks.push_back(Point3 ( 1.5, 1.5, 1.5*z)); + landmarks.push_back(Point3 ( 1.5,-1.5, 1.5*z)); + landmarks.push_back(Point3 (-2.0,-2.0, 2*z)); + landmarks.push_back(Point3 (-2.0, 2.0, 2*z)); + landmarks.push_back(Point3 ( 2.0, 2.0, 2*z)); + landmarks.push_back(Point3 ( 2.0,-2.0, 2*z)); + return landmarks ; } vector genCameraDefaultCalibration() { @@ -144,10 +149,10 @@ vector genCameraVariableCalibration() { return X ; } -boost::shared_ptr getOrdering(const vector& X, const vector& L) { +boost::shared_ptr getOrdering(const vector& cameras, const vector& landmarks) { boost::shared_ptr ordering(new Ordering); - for ( size_t i = 0 ; i < L.size() ; ++i ) ordering->push_back(Symbol('l', i)) ; - for ( size_t i = 0 ; i < X.size() ; ++i ) ordering->push_back(Symbol('x', i)) ; + for ( size_t i = 0 ; i < landmarks.size() ; ++i ) ordering->push_back(L(i)) ; + for ( size_t i = 0 ; i < cameras.size() ; ++i ) ordering->push_back(X(i)) ; return ordering ; } @@ -155,37 +160,37 @@ boost::shared_ptr getOrdering(const vector& X, const ve /* ************************************************************************* */ TEST( GeneralSFMFactor, optimize_defaultK ) { - vector L = genPoint3(); - vector X = genCameraDefaultCalibration(); + vector landmarks = genPoint3(); + vector cameras = genCameraDefaultCalibration(); // add measurement with noise Graph graph; - for ( size_t j = 0 ; j < X.size() ; ++j) { - for ( size_t i = 0 ; i < L.size() ; ++i) { - Point2 pt = X[j].project(L[i]) ; + for ( size_t j = 0 ; j < cameras.size() ; ++j) { + for ( size_t i = 0 ; i < landmarks.size() ; ++i) { + Point2 pt = cameras[j].project(landmarks[i]) ; graph.addMeasurement(j, i, pt, sigma1); } } - const size_t nMeasurements = X.size()*L.size() ; + const size_t nMeasurements = cameras.size()*landmarks.size() ; // add initial const double noise = baseline*0.1; Values values; - for ( size_t i = 0 ; i < X.size() ; ++i ) - values.insert(Symbol('x',i), X[i]) ; + for ( size_t i = 0 ; i < cameras.size() ; ++i ) + values.insert(X(i), cameras[i]) ; - for ( size_t i = 0 ; i < L.size() ; ++i ) { - Point3 pt(L[i].x()+noise*getGaussian(), - L[i].y()+noise*getGaussian(), - L[i].z()+noise*getGaussian()); - values.insert(Symbol('l',i), pt) ; + for ( size_t i = 0 ; i < landmarks.size() ; ++i ) { + Point3 pt(landmarks[i].x()+noise*getGaussian(), + landmarks[i].y()+noise*getGaussian(), + landmarks[i].z()+noise*getGaussian()); + values.insert(L(i), pt) ; } - graph.addCameraConstraint(0, X[0]); + graph.addCameraConstraint(0, cameras[0]); // Create an ordering of the variables - Ordering ordering = *getOrdering(X,L); + Ordering ordering = *getOrdering(cameras,landmarks); LevenbergMarquardtOptimizer optimizer(graph, values, ordering); Values final = optimizer.optimize(); EXPECT(optimizer.error() < 0.5 * 1e-5 * nMeasurements); @@ -193,42 +198,42 @@ TEST( GeneralSFMFactor, optimize_defaultK ) { /* ************************************************************************* */ TEST( GeneralSFMFactor, optimize_varK_SingleMeasurementError ) { - vector L = genPoint3(); - vector X = genCameraVariableCalibration(); + vector landmarks = genPoint3(); + vector cameras = genCameraVariableCalibration(); // add measurement with noise Graph graph; - for ( size_t j = 0 ; j < X.size() ; ++j) { - for ( size_t i = 0 ; i < L.size() ; ++i) { - Point2 pt = X[j].project(L[i]) ; + for ( size_t j = 0 ; j < cameras.size() ; ++j) { + for ( size_t i = 0 ; i < landmarks.size() ; ++i) { + Point2 pt = cameras[j].project(landmarks[i]) ; graph.addMeasurement(j, i, pt, sigma1); } } - const size_t nMeasurements = X.size()*L.size() ; + const size_t nMeasurements = cameras.size()*landmarks.size() ; // add initial const double noise = baseline*0.1; Values values; - for ( size_t i = 0 ; i < X.size() ; ++i ) - values.insert(Symbol('x',i), X[i]) ; + for ( size_t i = 0 ; i < cameras.size() ; ++i ) + values.insert(X(i), cameras[i]) ; // add noise only to the first landmark - for ( size_t i = 0 ; i < L.size() ; ++i ) { + for ( size_t i = 0 ; i < landmarks.size() ; ++i ) { if ( i == 0 ) { - Point3 pt(L[i].x()+noise*getGaussian(), - L[i].y()+noise*getGaussian(), - L[i].z()+noise*getGaussian()); - values.insert(Symbol('l',i), pt) ; + Point3 pt(landmarks[i].x()+noise*getGaussian(), + landmarks[i].y()+noise*getGaussian(), + landmarks[i].z()+noise*getGaussian()); + values.insert(L(i), pt) ; } else { - values.insert(Symbol('l',i), L[i]) ; + values.insert(L(i), landmarks[i]) ; } } - graph.addCameraConstraint(0, X[0]); + graph.addCameraConstraint(0, cameras[0]); const double reproj_error = 1e-5; - Ordering ordering = *getOrdering(X,L); + Ordering ordering = *getOrdering(cameras,landmarks); LevenbergMarquardtOptimizer optimizer(graph, values, ordering); Values final = optimizer.optimize(); EXPECT(optimizer.error() < 0.5 * reproj_error * nMeasurements); @@ -237,39 +242,39 @@ TEST( GeneralSFMFactor, optimize_varK_SingleMeasurementError ) { /* ************************************************************************* */ TEST( GeneralSFMFactor, optimize_varK_FixCameras ) { - vector L = genPoint3(); - vector X = genCameraVariableCalibration(); + vector landmarks = genPoint3(); + vector cameras = genCameraVariableCalibration(); // add measurement with noise const double noise = baseline*0.1; Graph graph; - for ( size_t j = 0 ; j < X.size() ; ++j) { - for ( size_t i = 0 ; i < L.size() ; ++i) { - Point2 pt = X[j].project(L[i]) ; + for ( size_t j = 0 ; j < cameras.size() ; ++j) { + for ( size_t i = 0 ; i < landmarks.size() ; ++i) { + Point2 pt = cameras[j].project(landmarks[i]) ; graph.addMeasurement(j, i, pt, sigma1); } } - const size_t nMeasurements = L.size()*X.size(); + const size_t nMeasurements = landmarks.size()*cameras.size(); Values values; - for ( size_t i = 0 ; i < X.size() ; ++i ) - values.insert(Symbol('x',i), X[i]) ; + for ( size_t i = 0 ; i < cameras.size() ; ++i ) + values.insert(X(i), cameras[i]) ; - for ( size_t i = 0 ; i < L.size() ; ++i ) { - Point3 pt(L[i].x()+noise*getGaussian(), - L[i].y()+noise*getGaussian(), - L[i].z()+noise*getGaussian()); - //Point3 pt(L[i].x(), L[i].y(), L[i].z()); - values.insert(Symbol('l',i), pt) ; + for ( size_t i = 0 ; i < landmarks.size() ; ++i ) { + Point3 pt(landmarks[i].x()+noise*getGaussian(), + landmarks[i].y()+noise*getGaussian(), + landmarks[i].z()+noise*getGaussian()); + //Point3 pt(landmarks[i].x(), landmarks[i].y(), landmarks[i].z()); + values.insert(L(i), pt) ; } - for ( size_t i = 0 ; i < X.size() ; ++i ) - graph.addCameraConstraint(i, X[i]); + for ( size_t i = 0 ; i < cameras.size() ; ++i ) + graph.addCameraConstraint(i, cameras[i]); const double reproj_error = 1e-5 ; - Ordering ordering = *getOrdering(X,L); + Ordering ordering = *getOrdering(cameras,landmarks); LevenbergMarquardtOptimizer optimizer(graph, values, ordering); Values final = optimizer.optimize(); EXPECT(optimizer.error() < 0.5 * reproj_error * nMeasurements); @@ -278,29 +283,29 @@ TEST( GeneralSFMFactor, optimize_varK_FixCameras ) { /* ************************************************************************* */ TEST( GeneralSFMFactor, optimize_varK_FixLandmarks ) { - vector L = genPoint3(); - vector X = genCameraVariableCalibration(); + vector landmarks = genPoint3(); + vector cameras = genCameraVariableCalibration(); // add measurement with noise Graph graph; - for ( size_t j = 0 ; j < X.size() ; ++j) { - for ( size_t i = 0 ; i < L.size() ; ++i) { - Point2 pt = X[j].project(L[i]) ; + for ( size_t j = 0 ; j < cameras.size() ; ++j) { + for ( size_t i = 0 ; i < landmarks.size() ; ++i) { + Point2 pt = cameras[j].project(landmarks[i]) ; graph.addMeasurement(j, i, pt, sigma1); } } - const size_t nMeasurements = L.size()*X.size(); + const size_t nMeasurements = landmarks.size()*cameras.size(); Values values; - for ( size_t i = 0 ; i < X.size() ; ++i ) { + for ( size_t i = 0 ; i < cameras.size() ; ++i ) { const double rot_noise = 1e-5, trans_noise = 1e-3, focal_noise = 1, skew_noise = 1e-5; if ( i == 0 ) { - values.insert(Symbol('x',i), X[i]) ; + values.insert(X(i), cameras[i]) ; } else { @@ -311,22 +316,22 @@ TEST( GeneralSFMFactor, optimize_varK_FixLandmarks ) { skew_noise, // s trans_noise, trans_noise // ux, uy ) ; - values.insert(Symbol('x',i), X[i].retract(delta)) ; + values.insert(X(i), cameras[i].retract(delta)) ; } } - for ( size_t i = 0 ; i < L.size() ; ++i ) { - values.insert(Symbol('l',i), L[i]) ; + for ( size_t i = 0 ; i < landmarks.size() ; ++i ) { + values.insert(L(i), landmarks[i]) ; } - // fix X0 and all landmarks, allow only the X[1] to move - graph.addCameraConstraint(0, X[0]); - for ( size_t i = 0 ; i < L.size() ; ++i ) - graph.addPoint3Constraint(i, L[i]); + // fix X0 and all landmarks, allow only the cameras[1] to move + graph.addCameraConstraint(0, cameras[0]); + for ( size_t i = 0 ; i < landmarks.size() ; ++i ) + graph.addPoint3Constraint(i, landmarks[i]); const double reproj_error = 1e-5 ; - Ordering ordering = *getOrdering(X,L); + Ordering ordering = *getOrdering(cameras,landmarks); LevenbergMarquardtOptimizer optimizer(graph, values, ordering); Values final = optimizer.optimize(); EXPECT(optimizer.error() < 0.5 * reproj_error * nMeasurements); @@ -334,43 +339,43 @@ TEST( GeneralSFMFactor, optimize_varK_FixLandmarks ) { /* ************************************************************************* */ TEST( GeneralSFMFactor, optimize_varK_BA ) { - vector L = genPoint3(); - vector X = genCameraVariableCalibration(); + vector landmarks = genPoint3(); + vector cameras = genCameraVariableCalibration(); // add measurement with noise Graph graph; - for ( size_t j = 0 ; j < X.size() ; ++j) { - for ( size_t i = 0 ; i < L.size() ; ++i) { - Point2 pt = X[j].project(L[i]) ; + for ( size_t j = 0 ; j < cameras.size() ; ++j) { + for ( size_t i = 0 ; i < landmarks.size() ; ++i) { + Point2 pt = cameras[j].project(landmarks[i]) ; graph.addMeasurement(j, i, pt, sigma1); } } - const size_t nMeasurements = X.size()*L.size() ; + const size_t nMeasurements = cameras.size()*landmarks.size() ; // add initial const double noise = baseline*0.1; Values values; - for ( size_t i = 0 ; i < X.size() ; ++i ) - values.insert(Symbol('x',i), X[i]) ; + for ( size_t i = 0 ; i < cameras.size() ; ++i ) + values.insert(X(i), cameras[i]) ; // add noise only to the first landmark - for ( size_t i = 0 ; i < L.size() ; ++i ) { - Point3 pt(L[i].x()+noise*getGaussian(), - L[i].y()+noise*getGaussian(), - L[i].z()+noise*getGaussian()); - values.insert(Symbol('l',i), pt) ; + for ( size_t i = 0 ; i < landmarks.size() ; ++i ) { + Point3 pt(landmarks[i].x()+noise*getGaussian(), + landmarks[i].y()+noise*getGaussian(), + landmarks[i].z()+noise*getGaussian()); + values.insert(L(i), pt) ; } // Constrain position of system with the first camera constrained to the origin - graph.addCameraConstraint(0, X[0]); + graph.addCameraConstraint(0, cameras[0]); // Constrain the scale of the problem with a soft range factor of 1m between the cameras - graph.add(RangeFactor(Symbol('x',0), Symbol('x',1), 2.0, sharedSigma(1, 10.0))); + graph.add(RangeFactor(X(0), X(1), 2.0, sharedSigma(1, 10.0))); const double reproj_error = 1e-5 ; - Ordering ordering = *getOrdering(X,L); + Ordering ordering = *getOrdering(cameras,landmarks); LevenbergMarquardtOptimizer optimizer(graph, values, ordering); Values final = optimizer.optimize(); EXPECT(optimizer.error() < 0.5 * reproj_error * nMeasurements); @@ -381,17 +386,17 @@ TEST(GeneralSFMFactor, GeneralCameraPoseRange) { // Tests range factor between a GeneralCamera and a Pose3 Graph graph; graph.addCameraConstraint(0, GeneralCamera()); - graph.add(RangeFactor(Symbol('x',0), Symbol('x',1), 2.0, sharedSigma(1, 1.0))); - graph.add(PriorFactor(Symbol('x',1), Pose3(Rot3(), Point3(1.0, 0.0, 0.0)), sharedSigma(6, 1.0))); + graph.add(RangeFactor(X(0), X(1), 2.0, sharedSigma(1, 1.0))); + graph.add(PriorFactor(X(1), Pose3(Rot3(), Point3(1.0, 0.0, 0.0)), sharedSigma(6, 1.0))); Values init; - init.insert(Symbol('x',0), GeneralCamera()); - init.insert(Symbol('x',1), Pose3(Rot3(), Point3(1.0,1.0,1.0))); + init.insert(X(0), GeneralCamera()); + init.insert(X(1), Pose3(Rot3(), Point3(1.0,1.0,1.0))); // The optimal value between the 2m range factor and 1m prior is 1.5m Values expected; - expected.insert(Symbol('x',0), GeneralCamera()); - expected.insert(Symbol('x',1), Pose3(Rot3(), Point3(1.5,0.0,0.0))); + expected.insert(X(0), GeneralCamera()); + expected.insert(X(1), Pose3(Rot3(), Point3(1.5,0.0,0.0))); LevenbergMarquardtParams params; params.absoluteErrorTol = 1e-9; @@ -405,17 +410,17 @@ TEST(GeneralSFMFactor, GeneralCameraPoseRange) { TEST(GeneralSFMFactor, CalibratedCameraPoseRange) { // Tests range factor between a CalibratedCamera and a Pose3 NonlinearFactorGraph graph; - graph.add(PriorFactor(Symbol('x',0), CalibratedCamera(), sharedSigma(6, 1.0))); - graph.add(RangeFactor(Symbol('x',0), Symbol('x',1), 2.0, sharedSigma(1, 1.0))); - graph.add(PriorFactor(Symbol('x',1), Pose3(Rot3(), Point3(1.0, 0.0, 0.0)), sharedSigma(6, 1.0))); + graph.add(PriorFactor(X(0), CalibratedCamera(), sharedSigma(6, 1.0))); + graph.add(RangeFactor(X(0), X(1), 2.0, sharedSigma(1, 1.0))); + graph.add(PriorFactor(X(1), Pose3(Rot3(), Point3(1.0, 0.0, 0.0)), sharedSigma(6, 1.0))); Values init; - init.insert(Symbol('x',0), CalibratedCamera()); - init.insert(Symbol('x',1), Pose3(Rot3(), Point3(1.0,1.0,1.0))); + init.insert(X(0), CalibratedCamera()); + init.insert(X(1), Pose3(Rot3(), Point3(1.0,1.0,1.0))); Values expected; - expected.insert(Symbol('x',0), CalibratedCamera(Pose3(Rot3(), Point3(-0.333333333333, 0, 0)))); - expected.insert(Symbol('x',1), Pose3(Rot3(), Point3(1.333333333333, 0, 0))); + expected.insert(X(0), CalibratedCamera(Pose3(Rot3(), Point3(-0.333333333333, 0, 0)))); + expected.insert(X(1), Pose3(Rot3(), Point3(1.333333333333, 0, 0))); LevenbergMarquardtParams params; params.absoluteErrorTol = 1e-9; diff --git a/gtsam/slam/tests/testGeneralSFMFactor_Cal3Bundler.cpp b/gtsam/slam/tests/testGeneralSFMFactor_Cal3Bundler.cpp index 34391c070..142c27e7e 100644 --- a/gtsam/slam/tests/testGeneralSFMFactor_Cal3Bundler.cpp +++ b/gtsam/slam/tests/testGeneralSFMFactor_Cal3Bundler.cpp @@ -10,32 +10,38 @@ * -------------------------------------------------------------------------- */ /** - * @file testGeneralSFMFactor.cpp + * @file testGeneralSFMFactor_Cal3Bundler.cpp * @date Dec 27, 2010 * @author nikai * @brief unit tests for GeneralSFMFactor */ -#include -#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include #include #include -using namespace boost; -#include -#include -#include -#include -#include -#include -#include -#include -#include +#include +#include using namespace std; using namespace gtsam; +// Convenience for named keys +using symbol_shorthand::X; +using symbol_shorthand::L; + typedef PinholeCamera GeneralCamera; typedef GeneralSFMFactor Projection; typedef NonlinearEquality CameraConstraint; @@ -45,16 +51,16 @@ typedef NonlinearEquality Point3Constraint; class Graph: public NonlinearFactorGraph { public: void addMeasurement(const int& i, const int& j, const Point2& z, const SharedNoiseModel& model) { - push_back(boost::make_shared(z, model, Symbol('x',i), Symbol('l',j))); + push_back(boost::make_shared(z, model, X(i), L(j))); } void addCameraConstraint(int j, const GeneralCamera& p) { - boost::shared_ptr factor(new CameraConstraint(Symbol('x', j), p)); + boost::shared_ptr factor(new CameraConstraint(X(j), p)); push_back(factor); } void addPoint3Constraint(int j, const Point3& p) { - boost::shared_ptr factor(new Point3Constraint(Symbol('l', j), p)); + boost::shared_ptr factor(new Point3Constraint(L(j), p)); push_back(factor); } @@ -98,14 +104,14 @@ TEST( GeneralSFMFactor, error ) { Point2 z(3.,0.); const SharedNoiseModel sigma(noiseModel::Unit::Create(1)); boost::shared_ptr - factor(new Projection(z, sigma, Symbol('x',1), Symbol('l',1))); + factor(new Projection(z, sigma, X(1), L(1))); // For the following configuration, the factor predicts 320,240 Values values; Rot3 R; Point3 t1(0,0,-6); Pose3 x1(R,t1); - values.insert(Symbol('x',1), GeneralCamera(x1)); - Point3 l1; values.insert(Symbol('l',1), l1); + values.insert(X(1), GeneralCamera(x1)); + Point3 l1; values.insert(L(1), l1); EXPECT(assert_equal(Vector_(2, -3.0, 0.0), factor->unwhitenedError(values))); } @@ -115,78 +121,78 @@ static const double baseline = 5.0 ; /* ************************************************************************* */ vector genPoint3() { const double z = 5; - vector L ; - L.push_back(Point3 (-1.0,-1.0, z)); - L.push_back(Point3 (-1.0, 1.0, z)); - L.push_back(Point3 ( 1.0, 1.0, z)); - L.push_back(Point3 ( 1.0,-1.0, z)); - L.push_back(Point3 (-1.5,-1.5, 1.5*z)); - L.push_back(Point3 (-1.5, 1.5, 1.5*z)); - L.push_back(Point3 ( 1.5, 1.5, 1.5*z)); - L.push_back(Point3 ( 1.5,-1.5, 1.5*z)); - L.push_back(Point3 (-2.0,-2.0, 2*z)); - L.push_back(Point3 (-2.0, 2.0, 2*z)); - L.push_back(Point3 ( 2.0, 2.0, 2*z)); - L.push_back(Point3 ( 2.0,-2.0, 2*z)); - return L ; + vector landmarks ; + landmarks.push_back(Point3 (-1.0,-1.0, z)); + landmarks.push_back(Point3 (-1.0, 1.0, z)); + landmarks.push_back(Point3 ( 1.0, 1.0, z)); + landmarks.push_back(Point3 ( 1.0,-1.0, z)); + landmarks.push_back(Point3 (-1.5,-1.5, 1.5*z)); + landmarks.push_back(Point3 (-1.5, 1.5, 1.5*z)); + landmarks.push_back(Point3 ( 1.5, 1.5, 1.5*z)); + landmarks.push_back(Point3 ( 1.5,-1.5, 1.5*z)); + landmarks.push_back(Point3 (-2.0,-2.0, 2*z)); + landmarks.push_back(Point3 (-2.0, 2.0, 2*z)); + landmarks.push_back(Point3 ( 2.0, 2.0, 2*z)); + landmarks.push_back(Point3 ( 2.0,-2.0, 2*z)); + return landmarks ; } vector genCameraDefaultCalibration() { - vector X ; - X.push_back(GeneralCamera(Pose3(eye(3),Point3(-baseline/2.0, 0.0, 0.0)))); - X.push_back(GeneralCamera(Pose3(eye(3),Point3( baseline/2.0, 0.0, 0.0)))); - return X ; + vector cameras ; + cameras.push_back(GeneralCamera(Pose3(eye(3),Point3(-baseline/2.0, 0.0, 0.0)))); + cameras.push_back(GeneralCamera(Pose3(eye(3),Point3( baseline/2.0, 0.0, 0.0)))); + return cameras ; } vector genCameraVariableCalibration() { const Cal3Bundler K(500,1e-3,1e-3); - vector X ; - X.push_back(GeneralCamera(Pose3(eye(3),Point3(-baseline/2.0, 0.0, 0.0)), K)); - X.push_back(GeneralCamera(Pose3(eye(3),Point3( baseline/2.0, 0.0, 0.0)), K)); - return X ; + vector cameras ; + cameras.push_back(GeneralCamera(Pose3(eye(3),Point3(-baseline/2.0, 0.0, 0.0)), K)); + cameras.push_back(GeneralCamera(Pose3(eye(3),Point3( baseline/2.0, 0.0, 0.0)), K)); + return cameras ; } -boost::shared_ptr getOrdering(const vector& X, const vector& L) { +boost::shared_ptr getOrdering(const std::vector& cameras, const std::vector& landmarks) { boost::shared_ptr ordering(new Ordering); - for ( size_t i = 0 ; i < L.size() ; ++i ) ordering->push_back(Symbol('l', i)) ; - for ( size_t i = 0 ; i < X.size() ; ++i ) ordering->push_back(Symbol('x', i)) ; + for ( size_t i = 0 ; i < landmarks.size() ; ++i ) ordering->push_back(L(i)) ; + for ( size_t i = 0 ; i < cameras.size() ; ++i ) ordering->push_back(X(i)) ; return ordering ; } /* ************************************************************************* */ TEST( GeneralSFMFactor, optimize_defaultK ) { - vector L = genPoint3(); - vector X = genCameraDefaultCalibration(); + vector landmarks = genPoint3(); + vector cameras = genCameraDefaultCalibration(); // add measurement with noise Graph graph; - for ( size_t j = 0 ; j < X.size() ; ++j) { - for ( size_t i = 0 ; i < L.size() ; ++i) { - Point2 pt = X[j].project(L[i]) ; + for ( size_t j = 0 ; j < cameras.size() ; ++j) { + for ( size_t i = 0 ; i < landmarks.size() ; ++i) { + Point2 pt = cameras[j].project(landmarks[i]) ; graph.addMeasurement(j, i, pt, sigma1); } } - const size_t nMeasurements = X.size()*L.size() ; + const size_t nMeasurements = cameras.size()*landmarks.size() ; // add initial const double noise = baseline*0.1; Values values; - for ( size_t i = 0 ; i < X.size() ; ++i ) - values.insert(Symbol('x',i), X[i]) ; + for ( size_t i = 0 ; i < cameras.size() ; ++i ) + values.insert(X(i), cameras[i]) ; - for ( size_t i = 0 ; i < L.size() ; ++i ) { - Point3 pt(L[i].x()+noise*getGaussian(), - L[i].y()+noise*getGaussian(), - L[i].z()+noise*getGaussian()); - values.insert(Symbol('l',i), pt) ; + for ( size_t i = 0 ; i < landmarks.size() ; ++i ) { + Point3 pt(landmarks[i].x()+noise*getGaussian(), + landmarks[i].y()+noise*getGaussian(), + landmarks[i].z()+noise*getGaussian()); + values.insert(L(i), pt) ; } - graph.addCameraConstraint(0, X[0]); + graph.addCameraConstraint(0, cameras[0]); // Create an ordering of the variables - Ordering ordering = *getOrdering(X,L); + Ordering ordering = *getOrdering(cameras,landmarks); LevenbergMarquardtOptimizer optimizer(graph, values, ordering); Values final = optimizer.optimize(); EXPECT(optimizer.error() < 0.5 * 1e-5 * nMeasurements); @@ -194,42 +200,42 @@ TEST( GeneralSFMFactor, optimize_defaultK ) { /* ************************************************************************* */ TEST( GeneralSFMFactor, optimize_varK_SingleMeasurementError ) { - vector L = genPoint3(); - vector X = genCameraVariableCalibration(); + vector landmarks = genPoint3(); + vector cameras = genCameraVariableCalibration(); // add measurement with noise Graph graph; - for ( size_t j = 0 ; j < X.size() ; ++j) { - for ( size_t i = 0 ; i < L.size() ; ++i) { - Point2 pt = X[j].project(L[i]) ; + for ( size_t j = 0 ; j < cameras.size() ; ++j) { + for ( size_t i = 0 ; i < landmarks.size() ; ++i) { + Point2 pt = cameras[j].project(landmarks[i]) ; graph.addMeasurement(j, i, pt, sigma1); } } - const size_t nMeasurements = X.size()*L.size() ; + const size_t nMeasurements = cameras.size()*landmarks.size() ; // add initial const double noise = baseline*0.1; Values values; - for ( size_t i = 0 ; i < X.size() ; ++i ) - values.insert(Symbol('x',i), X[i]) ; + for ( size_t i = 0 ; i < cameras.size() ; ++i ) + values.insert(X(i), cameras[i]) ; // add noise only to the first landmark - for ( size_t i = 0 ; i < L.size() ; ++i ) { + for ( size_t i = 0 ; i < landmarks.size() ; ++i ) { if ( i == 0 ) { - Point3 pt(L[i].x()+noise*getGaussian(), - L[i].y()+noise*getGaussian(), - L[i].z()+noise*getGaussian()); - values.insert(Symbol('l',i), pt) ; + Point3 pt(landmarks[i].x()+noise*getGaussian(), + landmarks[i].y()+noise*getGaussian(), + landmarks[i].z()+noise*getGaussian()); + values.insert(L(i), pt) ; } else { - values.insert(Symbol('l',i), L[i]) ; + values.insert(L(i), landmarks[i]) ; } } - graph.addCameraConstraint(0, X[0]); + graph.addCameraConstraint(0, cameras[0]); const double reproj_error = 1e-5; - Ordering ordering = *getOrdering(X,L); + Ordering ordering = *getOrdering(cameras,landmarks); LevenbergMarquardtOptimizer optimizer(graph, values, ordering); Values final = optimizer.optimize(); EXPECT(optimizer.error() < 0.5 * reproj_error * nMeasurements); @@ -238,39 +244,39 @@ TEST( GeneralSFMFactor, optimize_varK_SingleMeasurementError ) { /* ************************************************************************* */ TEST( GeneralSFMFactor, optimize_varK_FixCameras ) { - vector L = genPoint3(); - vector X = genCameraVariableCalibration(); + vector landmarks = genPoint3(); + vector cameras = genCameraVariableCalibration(); // add measurement with noise const double noise = baseline*0.1; Graph graph; - for ( size_t j = 0 ; j < X.size() ; ++j) { - for ( size_t i = 0 ; i < L.size() ; ++i) { - Point2 pt = X[j].project(L[i]) ; + for ( size_t j = 0 ; j < cameras.size() ; ++j) { + for ( size_t i = 0 ; i < landmarks.size() ; ++i) { + Point2 pt = cameras[j].project(landmarks[i]) ; graph.addMeasurement(j, i, pt, sigma1); } } - const size_t nMeasurements = L.size()*X.size(); + const size_t nMeasurements = landmarks.size()*cameras.size(); Values values; - for ( size_t i = 0 ; i < X.size() ; ++i ) - values.insert(Symbol('x',i), X[i]) ; + for ( size_t i = 0 ; i < cameras.size() ; ++i ) + values.insert(X(i), cameras[i]) ; - for ( size_t i = 0 ; i < L.size() ; ++i ) { - Point3 pt(L[i].x()+noise*getGaussian(), - L[i].y()+noise*getGaussian(), - L[i].z()+noise*getGaussian()); - //Point3 pt(L[i].x(), L[i].y(), L[i].z()); - values.insert(Symbol('l',i), pt) ; + for ( size_t i = 0 ; i < landmarks.size() ; ++i ) { + Point3 pt(landmarks[i].x()+noise*getGaussian(), + landmarks[i].y()+noise*getGaussian(), + landmarks[i].z()+noise*getGaussian()); + //Point3 pt(landmarks[i].x(), landmarks[i].y(), landmarks[i].z()); + values.insert(L(i), pt) ; } - for ( size_t i = 0 ; i < X.size() ; ++i ) - graph.addCameraConstraint(i, X[i]); + for ( size_t i = 0 ; i < cameras.size() ; ++i ) + graph.addCameraConstraint(i, cameras[i]); const double reproj_error = 1e-5 ; - Ordering ordering = *getOrdering(X,L); + Ordering ordering = *getOrdering(cameras,landmarks); LevenbergMarquardtOptimizer optimizer(graph, values, ordering); Values final = optimizer.optimize(); EXPECT(optimizer.error() < 0.5 * reproj_error * nMeasurements); @@ -279,27 +285,27 @@ TEST( GeneralSFMFactor, optimize_varK_FixCameras ) { /* ************************************************************************* */ TEST( GeneralSFMFactor, optimize_varK_FixLandmarks ) { - vector L = genPoint3(); - vector X = genCameraVariableCalibration(); + vector landmarks = genPoint3(); + vector cameras = genCameraVariableCalibration(); // add measurement with noise Graph graph; - for ( size_t j = 0 ; j < X.size() ; ++j) { - for ( size_t i = 0 ; i < L.size() ; ++i) { - Point2 pt = X[j].project(L[i]) ; + for ( size_t j = 0 ; j < cameras.size() ; ++j) { + for ( size_t i = 0 ; i < landmarks.size() ; ++i) { + Point2 pt = cameras[j].project(landmarks[i]) ; graph.addMeasurement(j, i, pt, sigma1); } } - const size_t nMeasurements = L.size()*X.size(); + const size_t nMeasurements = landmarks.size()*cameras.size(); Values values; - for ( size_t i = 0 ; i < X.size() ; ++i ) { + for ( size_t i = 0 ; i < cameras.size() ; ++i ) { const double rot_noise = 1e-5, trans_noise = 1e-3, focal_noise = 1, distort_noise = 1e-3; if ( i == 0 ) { - values.insert(Symbol('x',i), X[i]) ; + values.insert(X(i), cameras[i]) ; } else { @@ -308,22 +314,22 @@ TEST( GeneralSFMFactor, optimize_varK_FixLandmarks ) { trans_noise, trans_noise, trans_noise, // translation focal_noise, distort_noise, distort_noise // f, k1, k2 ) ; - values.insert(Symbol('x',i), X[i].retract(delta)) ; + values.insert(X(i), cameras[i].retract(delta)) ; } } - for ( size_t i = 0 ; i < L.size() ; ++i ) { - values.insert(Symbol('l',i), L[i]) ; + for ( size_t i = 0 ; i < landmarks.size() ; ++i ) { + values.insert(L(i), landmarks[i]) ; } - // fix X0 and all landmarks, allow only the X[1] to move - graph.addCameraConstraint(0, X[0]); - for ( size_t i = 0 ; i < L.size() ; ++i ) - graph.addPoint3Constraint(i, L[i]); + // fix X0 and all landmarks, allow only the cameras[1] to move + graph.addCameraConstraint(0, cameras[0]); + for ( size_t i = 0 ; i < landmarks.size() ; ++i ) + graph.addPoint3Constraint(i, landmarks[i]); const double reproj_error = 1e-5 ; - Ordering ordering = *getOrdering(X,L); + Ordering ordering = *getOrdering(cameras,landmarks); LevenbergMarquardtOptimizer optimizer(graph, values, ordering); Values final = optimizer.optimize(); EXPECT(optimizer.error() < 0.5 * reproj_error * nMeasurements); @@ -331,43 +337,43 @@ TEST( GeneralSFMFactor, optimize_varK_FixLandmarks ) { /* ************************************************************************* */ TEST( GeneralSFMFactor, optimize_varK_BA ) { - vector L = genPoint3(); - vector X = genCameraVariableCalibration(); + vector landmarks = genPoint3(); + vector cameras = genCameraVariableCalibration(); // add measurement with noise Graph graph; - for ( size_t j = 0 ; j < X.size() ; ++j) { - for ( size_t i = 0 ; i < L.size() ; ++i) { - Point2 pt = X[j].project(L[i]) ; + for ( size_t j = 0 ; j < cameras.size() ; ++j) { + for ( size_t i = 0 ; i < landmarks.size() ; ++i) { + Point2 pt = cameras[j].project(landmarks[i]) ; graph.addMeasurement(j, i, pt, sigma1); } } - const size_t nMeasurements = X.size()*L.size() ; + const size_t nMeasurements = cameras.size()*landmarks.size() ; // add initial const double noise = baseline*0.1; Values values; - for ( size_t i = 0 ; i < X.size() ; ++i ) - values.insert(Symbol('x',i), X[i]) ; + for ( size_t i = 0 ; i < cameras.size() ; ++i ) + values.insert(X(i), cameras[i]) ; // add noise only to the first landmark - for ( size_t i = 0 ; i < L.size() ; ++i ) { - Point3 pt(L[i].x()+noise*getGaussian(), - L[i].y()+noise*getGaussian(), - L[i].z()+noise*getGaussian()); - values.insert(Symbol('l',i), pt) ; + for ( size_t i = 0 ; i < landmarks.size() ; ++i ) { + Point3 pt(landmarks[i].x()+noise*getGaussian(), + landmarks[i].y()+noise*getGaussian(), + landmarks[i].z()+noise*getGaussian()); + values.insert(L(i), pt) ; } // Constrain position of system with the first camera constrained to the origin - graph.addCameraConstraint(0, X[0]); + graph.addCameraConstraint(X(0), cameras[0]); // Constrain the scale of the problem with a soft range factor of 1m between the cameras - graph.add(RangeFactor(Symbol('x',0), Symbol('x',1), 2.0, sharedSigma(1, 10.0))); + graph.add(RangeFactor(X(0), X(1), 2.0, sharedSigma(1, 10.0))); const double reproj_error = 1e-5 ; - Ordering ordering = *getOrdering(X,L); + Ordering ordering = *getOrdering(cameras,landmarks); LevenbergMarquardtOptimizer optimizer(graph, values, ordering); Values final = optimizer.optimize(); EXPECT(optimizer.error() < 0.5 * reproj_error * nMeasurements); diff --git a/gtsam/slam/tests/testPlanarSLAM.cpp b/gtsam/slam/tests/testPlanarSLAM.cpp index 4b69252b3..c5d77faa3 100644 --- a/gtsam/slam/tests/testPlanarSLAM.cpp +++ b/gtsam/slam/tests/testPlanarSLAM.cpp @@ -14,20 +14,21 @@ * @author Frank Dellaert **/ +#include +#include +#include +#include + #include #include -#include -#include -#include - using namespace std; using namespace gtsam; -using namespace planarSLAM; // some shared test values -static Pose2 x1, x2(1, 1, 0), x3(1, 1, M_PI/4.0); +static Pose2 x1, x2(1, 1, 0), x3(1, 1, M_PI_4); static Point2 l1(1, 0), l2(1, 1), l3(2, 2), l4(1, 3); +static Symbol i2('x',2), i3('x',3), j3('l',3); SharedNoiseModel sigma(noiseModel::Isotropic::Sigma(1,0.1)), @@ -37,7 +38,7 @@ SharedNoiseModel /* ************************************************************************* */ TEST( planarSLAM, PriorFactor_equals ) { - planarSLAM::Prior factor1(PoseKey(2), x1, I3), factor2(PoseKey(2), x2, I3); + planarSLAM::Prior factor1(i2, x1, I3), factor2(i2, x2, I3); EXPECT(assert_equal(factor1, factor1, 1e-5)); EXPECT(assert_equal(factor2, factor2, 1e-5)); EXPECT(assert_inequal(factor1, factor2, 1e-5)); @@ -47,13 +48,13 @@ TEST( planarSLAM, PriorFactor_equals ) TEST( planarSLAM, BearingFactor ) { // Create factor - Rot2 z = Rot2::fromAngle(M_PI/4.0 + 0.1); // h(x) - z = -0.1 - planarSLAM::Bearing factor(PoseKey(2), PointKey(3), z, sigma); + Rot2 z = Rot2::fromAngle(M_PI_4 + 0.1); // h(x) - z = -0.1 + planarSLAM::Bearing factor(i2, j3, z, sigma); // create config planarSLAM::Values c; - c.insert(PoseKey(2), x2); - c.insert(PointKey(3), l3); + c.insert(i2, x2); + c.insert(j3, l3); // Check error Vector actual = factor.unwhitenedError(c); @@ -64,8 +65,8 @@ TEST( planarSLAM, BearingFactor ) TEST( planarSLAM, BearingFactor_equals ) { planarSLAM::Bearing - factor1(PoseKey(2), PointKey(3), Rot2::fromAngle(0.1), sigma), - factor2(PoseKey(2), PointKey(3), Rot2::fromAngle(2.3), sigma); + factor1(i2, j3, Rot2::fromAngle(0.1), sigma), + factor2(i2, j3, Rot2::fromAngle(2.3), sigma); EXPECT(assert_equal(factor1, factor1, 1e-5)); EXPECT(assert_equal(factor2, factor2, 1e-5)); EXPECT(assert_inequal(factor1, factor2, 1e-5)); @@ -76,12 +77,12 @@ TEST( planarSLAM, RangeFactor ) { // Create factor double z(sqrt(2.0) - 0.22); // h(x) - z = 0.22 - planarSLAM::Range factor(PoseKey(2), PointKey(3), z, sigma); + planarSLAM::Range factor(i2, j3, z, sigma); // create config planarSLAM::Values c; - c.insert(PoseKey(2), x2); - c.insert(PointKey(3), l3); + c.insert(i2, x2); + c.insert(j3, l3); // Check error Vector actual = factor.unwhitenedError(c); @@ -91,7 +92,7 @@ TEST( planarSLAM, RangeFactor ) /* ************************************************************************* */ TEST( planarSLAM, RangeFactor_equals ) { - planarSLAM::Range factor1(PoseKey(2), PointKey(3), 1.2, sigma), factor2(PoseKey(2), PointKey(3), 7.2, sigma); + planarSLAM::Range factor1(i2, j3, 1.2, sigma), factor2(i2, j3, 7.2, sigma); EXPECT(assert_equal(factor1, factor1, 1e-5)); EXPECT(assert_equal(factor2, factor2, 1e-5)); EXPECT(assert_inequal(factor1, factor2, 1e-5)); @@ -101,14 +102,14 @@ TEST( planarSLAM, RangeFactor_equals ) TEST( planarSLAM, BearingRangeFactor ) { // Create factor - Rot2 r = Rot2::fromAngle(M_PI/4.0 + 0.1); // h(x) - z = -0.1 + Rot2 r = Rot2::fromAngle(M_PI_4 + 0.1); // h(x) - z = -0.1 double b(sqrt(2.0) - 0.22); // h(x) - z = 0.22 - planarSLAM::BearingRange factor(PoseKey(2), PointKey(3), r, b, sigma2); + planarSLAM::BearingRange factor(i2, j3, r, b, sigma2); // create config planarSLAM::Values c; - c.insert(PoseKey(2), x2); - c.insert(PointKey(3), l3); + c.insert(i2, x2); + c.insert(j3, l3); // Check error Vector actual = factor.unwhitenedError(c); @@ -119,8 +120,8 @@ TEST( planarSLAM, BearingRangeFactor ) TEST( planarSLAM, BearingRangeFactor_equals ) { planarSLAM::BearingRange - factor1(PoseKey(2), PointKey(3), Rot2::fromAngle(0.1), 7.3, sigma2), - factor2(PoseKey(2), PointKey(3), Rot2::fromAngle(3), 2.0, sigma2); + factor1(i2, j3, Rot2::fromAngle(0.1), 7.3, sigma2), + factor2(i2, j3, Rot2::fromAngle(3), 2.0, sigma2); EXPECT(assert_equal(factor1, factor1, 1e-5)); EXPECT(assert_equal(factor2, factor2, 1e-5)); EXPECT(assert_inequal(factor1, factor2, 1e-5)); @@ -130,13 +131,13 @@ TEST( planarSLAM, BearingRangeFactor_equals ) TEST( planarSLAM, BearingRangeFactor_poses ) { typedef BearingRangeFactor PoseBearingRange; - PoseBearingRange actual(PoseKey(2), PoseKey(3), Rot2::fromDegrees(60.0), 12.3, sigma2); + PoseBearingRange actual(2, 3, Rot2::fromDegrees(60.0), 12.3, sigma2); } /* ************************************************************************* */ TEST( planarSLAM, PoseConstraint_equals ) { - planarSLAM::Constraint factor1(PoseKey(2), x2), factor2(PoseKey(2), x3); + planarSLAM::Constraint factor1(i2, x2), factor2(i2, x3); EXPECT(assert_equal(factor1, factor1, 1e-5)); EXPECT(assert_equal(factor2, factor2, 1e-5)); EXPECT(assert_inequal(factor1, factor2, 1e-5)); @@ -147,26 +148,26 @@ TEST( planarSLAM, constructor ) { // create config planarSLAM::Values c; - c.insert(PoseKey(2), x2); - c.insert(PoseKey(3), x3); - c.insert(PointKey(3), l3); + c.insert(i2, x2); + c.insert(i3, x3); + c.insert(j3, l3); // create graph planarSLAM::Graph G; // Add pose constraint - G.addPoseConstraint(2, x2); // make it feasible :-) + G.addPoseConstraint(i2, x2); // make it feasible :-) // Add odometry - G.addOdometry(2, 3, Pose2(0, 0, M_PI/4.0), I3); + G.addOdometry(i2, i3, Pose2(0, 0, M_PI_4), I3); // Create bearing factor - Rot2 z1 = Rot2::fromAngle(M_PI/4.0 + 0.1); // h(x) - z = -0.1 - G.addBearing(2, 3, z1, sigma); + Rot2 z1 = Rot2::fromAngle(M_PI_4 + 0.1); // h(x) - z = -0.1 + G.addBearing(i2, j3, z1, sigma); // Create range factor double z2(sqrt(2.0) - 0.22); // h(x) - z = 0.22 - G.addRange(2, 3, z2, sigma); + G.addRange(i2, j3, z2, sigma); Vector expected0 = Vector_(3, 0.0, 0.0, 0.0); Vector expected1 = Vector_(3, 0.0, 0.0, 0.0); diff --git a/gtsam/slam/tests/testPose2SLAM.cpp b/gtsam/slam/tests/testPose2SLAM.cpp index 978d001a5..55558b106 100644 --- a/gtsam/slam/tests/testPose2SLAM.cpp +++ b/gtsam/slam/tests/testPose2SLAM.cpp @@ -32,7 +32,6 @@ using namespace boost::assign; using namespace std; typedef pose2SLAM::Odometry Pose2Factor; -using pose2SLAM::PoseKey; // common measurement covariance static double sx=0.5, sy=0.5,st=0.1; @@ -42,23 +41,31 @@ static Matrix cov(Matrix_(3, 3, 0.0, 0.0, st*st )); static noiseModel::Gaussian::shared_ptr covariance(noiseModel::Gaussian::Covariance(cov)); -//static noiseModel::Gaussian::shared_ptr I3(noiseModel::Unit::Create(3)); -const Key kx0 = Symbol('x',0), kx1 = Symbol('x',1), kx2 = Symbol('x',2), kx3 = Symbol('x',3), kx4 = Symbol('x',4), kx5 = Symbol('x',5), kl1 = Symbol('l',1); +/* ************************************************************************* */ +TEST_UNSAFE( Pose2SLAM, XYT ) +{ + pose2SLAM::Values values; + values.insertPose(1,Pose2(1,2,3)); + values.insertPose(2,Pose2(4,5,6)); + EXPECT(assert_equal(Vector_(2,1.0,4.0),values.xs())); + EXPECT(assert_equal(Vector_(2,2.0,5.0),values.ys())); + EXPECT(assert_equal(Vector_(2,3.0,6.0-2*M_PI),values.thetas())); +} /* ************************************************************************* */ // Test constraint, small displacement Vector f1(const Pose2& pose1, const Pose2& pose2) { Pose2 z(2.1130913087, 0.468461064817, 0.436332312999); - Pose2Factor constraint(PoseKey(1), PoseKey(2), z, covariance); + Pose2Factor constraint(1, 2, z, covariance); return constraint.evaluateError(pose1, pose2); } -TEST( Pose2SLAM, constraint1 ) +TEST_UNSAFE( Pose2SLAM, constraint1 ) { // create a factor between unknown poses p1 and p2 Pose2 pose1, pose2(2.1130913087, 0.468461064817, 0.436332312999); - Pose2Factor constraint(PoseKey(1), PoseKey(2), pose2, covariance); + Pose2Factor constraint(1, 2, pose2, covariance); Matrix H1, H2; Vector actual = constraint.evaluateError(pose1, pose2, H1, H2); @@ -72,16 +79,16 @@ TEST( Pose2SLAM, constraint1 ) /* ************************************************************************* */ // Test constraint, large displacement Vector f2(const Pose2& pose1, const Pose2& pose2) { - Pose2 z(2,2,M_PI/2.0); - Pose2Factor constraint(PoseKey(1), PoseKey(2), z, covariance); + Pose2 z(2,2,M_PI_2); + Pose2Factor constraint(1, 2, z, covariance); return constraint.evaluateError(pose1, pose2); } -TEST( Pose2SLAM, constraint2 ) +TEST_UNSAFE( Pose2SLAM, constraint2 ) { // create a factor between unknown poses p1 and p2 - Pose2 pose1, pose2(2,2,M_PI/2.0); - Pose2Factor constraint(PoseKey(1), PoseKey(2), pose2, covariance); + Pose2 pose1, pose2(2,2,M_PI_2); + Pose2Factor constraint(1, 2, pose2, covariance); Matrix H1, H2; Vector actual = constraint.evaluateError(pose1, pose2, H1, H2); @@ -93,10 +100,10 @@ TEST( Pose2SLAM, constraint2 ) } /* ************************************************************************* */ -TEST( Pose2SLAM, constructor ) +TEST_UNSAFE( Pose2SLAM, constructor ) { // create a factor between unknown poses p1 and p2 - Pose2 measured(2,2,M_PI/2.0); + Pose2 measured(2,2,M_PI_2); pose2SLAM::Graph graph; graph.addOdometry(1,2,measured, covariance); // get the size of the graph @@ -107,20 +114,20 @@ TEST( Pose2SLAM, constructor ) } /* ************************************************************************* */ -TEST( Pose2SLAM, linearization ) +TEST_UNSAFE( Pose2SLAM, linearization ) { // create a factor between unknown poses p1 and p2 - Pose2 measured(2,2,M_PI/2.0); - Pose2Factor constraint(PoseKey(1), PoseKey(2), measured, covariance); + Pose2 measured(2,2,M_PI_2); + Pose2Factor constraint(1, 2, measured, covariance); pose2SLAM::Graph graph; graph.addOdometry(1,2,measured, covariance); // Choose a linearization point - Pose2 p1(1.1,2,M_PI/2.0); // robot at (1.1,2) looking towards y (ground truth is at 1,2, see testPose2) + Pose2 p1(1.1,2,M_PI_2); // robot at (1.1,2) looking towards y (ground truth is at 1,2, see testPose2) Pose2 p2(-1,4.1,M_PI); // robot at (-1,4) looking at negative (ground truth is at 4.1,2) pose2SLAM::Values config; - config.insert(pose2SLAM::PoseKey(1),p1); - config.insert(pose2SLAM::PoseKey(2),p2); + config.insert(1,p1); + config.insert(2,p2); // Linearize Ordering ordering(*config.orderingArbitrary()); boost::shared_ptr > lfg_linearized = graph.linearize(config, ordering); @@ -140,27 +147,27 @@ TEST( Pose2SLAM, linearization ) Vector b = Vector_(3,-0.1/sx,0.1/sy,0.0); SharedDiagonal probModel1 = noiseModel::Unit::Create(3); - lfg_expected.push_back(JacobianFactor::shared_ptr(new JacobianFactor(ordering[kx1], A1, ordering[kx2], A2, b, probModel1))); + lfg_expected.push_back(JacobianFactor::shared_ptr(new JacobianFactor(ordering[1], A1, ordering[2], A2, b, probModel1))); CHECK(assert_equal(lfg_expected, *lfg_linearized)); } /* ************************************************************************* */ -TEST(Pose2SLAM, optimize) { +TEST_UNSAFE(Pose2SLAM, optimize) { // create a Pose graph with one equality constraint and one measurement pose2SLAM::Graph fg; fg.addPoseConstraint(0, Pose2(0,0,0)); - fg.addOdometry(0, 1, Pose2(1,2,M_PI/2.0), covariance); + fg.addOdometry(0, 1, Pose2(1,2,M_PI_2), covariance); // Create initial config Values initial; - initial.insert(pose2SLAM::PoseKey(0), Pose2(0,0,0)); - initial.insert(pose2SLAM::PoseKey(1), Pose2(0,0,0)); + initial.insert(0, Pose2(0,0,0)); + initial.insert(1, Pose2(0,0,0)); // Choose an ordering and optimize Ordering ordering; - ordering += kx0, kx1; + ordering += 0, 1; LevenbergMarquardtParams params; params.relativeErrorTol = 1e-15; @@ -169,26 +176,26 @@ TEST(Pose2SLAM, optimize) { // Check with expected config Values expected; - expected.insert(pose2SLAM::PoseKey(0), Pose2(0,0,0)); - expected.insert(pose2SLAM::PoseKey(1), Pose2(1,2,M_PI/2.0)); + expected.insert(0, Pose2(0,0,0)); + expected.insert(1, Pose2(1,2,M_PI_2)); CHECK(assert_equal(expected, actual)); // Check marginals Marginals marginals = fg.marginals(actual); // Matrix expectedP0 = Infinity, as we have a pose constraint !? - // Matrix actualP0 = marginals.marginalCovariance(pose2SLAM::PoseKey(0)); + // Matrix actualP0 = marginals.marginalCovariance(0); // EQUALITY(expectedP0, actualP0); Matrix expectedP1 = cov; // the second pose really should have just the noise covariance - Matrix actualP1 = marginals.marginalCovariance(pose2SLAM::PoseKey(1)); + Matrix actualP1 = marginals.marginalCovariance(1); EQUALITY(expectedP1, actualP1); } /* ************************************************************************* */ -// test optimization with 3 poses -TEST(Pose2SLAM, optimizeThreePoses) { +// test optimization with 3 poses, note we use plain Keys here, not symbols +TEST_UNSAFE(Pose2SLAM, optimizeThreePoses) { // Create a hexagon of poses - pose2SLAM::Values hexagon = pose2SLAM::circle(3,1.0); + pose2SLAM::Values hexagon = pose2SLAM::Values::Circle(3,1.0); Pose2 p0 = hexagon.pose(0), p1 = hexagon.pose(1); // create a Pose graph with one equality constraint and one measurement @@ -207,7 +214,7 @@ TEST(Pose2SLAM, optimizeThreePoses) { // Choose an ordering Ordering ordering; - ordering += kx0,kx1,kx2; + ordering += 0,1,2; // optimize LevenbergMarquardtParams params; @@ -224,19 +231,19 @@ TEST(Pose2SLAM, optimizeThreePoses) { TEST_UNSAFE(Pose2SLAM, optimizeCircle) { // Create a hexagon of poses - pose2SLAM::Values hexagon = pose2SLAM::circle(6,1.0); + pose2SLAM::Values hexagon = pose2SLAM::Values::Circle(6,1.0); Pose2 p0 = hexagon.pose(0), p1 = hexagon.pose(1); // create a Pose graph with one equality constraint and one measurement pose2SLAM::Graph fg; fg.addPoseConstraint(0, p0); Pose2 delta = p0.between(p1); - fg.addOdometry(0, 1, delta, covariance); + fg.addOdometry(0,1, delta, covariance); fg.addOdometry(1,2, delta, covariance); fg.addOdometry(2,3, delta, covariance); fg.addOdometry(3,4, delta, covariance); fg.addOdometry(4,5, delta, covariance); - fg.addOdometry(5, 0, delta, covariance); + fg.addOdometry(5,0, delta, covariance); // Create initial config pose2SLAM::Values initial; @@ -249,7 +256,7 @@ TEST_UNSAFE(Pose2SLAM, optimizeCircle) { // Choose an ordering Ordering ordering; - ordering += kx0,kx1,kx2,kx3,kx4,kx5; + ordering += 0,1,2,3,4,5; // optimize LevenbergMarquardtParams params; @@ -261,7 +268,7 @@ TEST_UNSAFE(Pose2SLAM, optimizeCircle) { CHECK(assert_equal((const Values&)hexagon, actual)); // Check loop closure - CHECK(assert_equal(delta, actual.at(PoseKey(5)).between(actual.at(PoseKey(0))))); + CHECK(assert_equal(delta, actual.at(5).between(actual.at(0)))); // Pose2SLAMOptimizer myOptimizer("3"); @@ -299,7 +306,7 @@ TEST_UNSAFE(Pose2SLAM, optimizeCircle) { } /* ************************************************************************* */ -TEST(Pose2SLAM, optimize2) { +TEST_UNSAFE(Pose2SLAM, optimize2) { // Pose2SLAMOptimizer myOptimizer("100"); // Matrix A1 = myOptimizer.a1(); // Matrix A2 = myOptimizer.a2(); @@ -317,7 +324,7 @@ TEST(Pose2SLAM, optimize2) { } ///* ************************************************************************* */ -// SL-NEEDED? TEST(Pose2SLAM, findMinimumSpanningTree) { +// SL-NEEDED? TEST_UNSAFE(Pose2SLAM, findMinimumSpanningTree) { // pose2SLAM::Graph G, T, C; // G.addConstraint(1, 2, Pose2(0.,0.,0.), I3); // G.addConstraint(1, 3, Pose2(0.,0.,0.), I3); @@ -331,7 +338,7 @@ TEST(Pose2SLAM, optimize2) { //} // ///* ************************************************************************* */ -// SL-NEEDED? TEST(Pose2SLAM, split) { +// SL-NEEDED? TEST_UNSAFE(Pose2SLAM, split) { // pose2SLAM::Graph G, T, C; // G.addConstraint(1, 2, Pose2(0.,0.,0.), I3); // G.addConstraint(1, 3, Pose2(0.,0.,0.), I3); @@ -350,37 +357,37 @@ TEST(Pose2SLAM, optimize2) { using namespace pose2SLAM; /* ************************************************************************* */ -TEST(Pose2Values, pose2Circle ) +TEST_UNSAFE(Pose2Values, pose2Circle ) { // expected is 4 poses tangent to circle with radius 1m pose2SLAM::Values expected; - expected.insert(pose2SLAM::PoseKey(0), Pose2( 1, 0, M_PI/2.0)); - expected.insert(pose2SLAM::PoseKey(1), Pose2( 0, 1, - M_PI )); - expected.insert(pose2SLAM::PoseKey(2), Pose2(-1, 0, - M_PI/2.0)); - expected.insert(pose2SLAM::PoseKey(3), Pose2( 0, -1, 0 )); + expected.insert(0, Pose2( 1, 0, M_PI_2)); + expected.insert(1, Pose2( 0, 1, - M_PI )); + expected.insert(2, Pose2(-1, 0, - M_PI_2)); + expected.insert(3, Pose2( 0, -1, 0 )); - pose2SLAM::Values actual = pose2SLAM::circle(4,1.0); + pose2SLAM::Values actual = pose2SLAM::Values::Circle(4,1.0); CHECK(assert_equal(expected,actual)); } /* ************************************************************************* */ -TEST(Pose2SLAM, expmap ) +TEST_UNSAFE(Pose2SLAM, expmap ) { // expected is circle shifted to right pose2SLAM::Values expected; - expected.insert(pose2SLAM::PoseKey(0), Pose2( 1.1, 0, M_PI/2.0)); - expected.insert(pose2SLAM::PoseKey(1), Pose2( 0.1, 1, - M_PI )); - expected.insert(pose2SLAM::PoseKey(2), Pose2(-0.9, 0, - M_PI/2.0)); - expected.insert(pose2SLAM::PoseKey(3), Pose2( 0.1, -1, 0 )); + expected.insert(0, Pose2( 1.1, 0, M_PI_2)); + expected.insert(1, Pose2( 0.1, 1, - M_PI )); + expected.insert(2, Pose2(-0.9, 0, - M_PI_2)); + expected.insert(3, Pose2( 0.1, -1, 0 )); // Note expmap coordinates are in local coordinates, so shifting to right requires thought !!! - pose2SLAM::Values circle(pose2SLAM::circle(4,1.0)); + pose2SLAM::Values circle = pose2SLAM::Values::Circle(4,1.0); Ordering ordering(*circle.orderingArbitrary()); VectorValues delta(circle.dims(ordering)); - delta[ordering[pose2SLAM::PoseKey(0)]] = Vector_(3, 0.0,-0.1,0.0); - delta[ordering[pose2SLAM::PoseKey(1)]] = Vector_(3, -0.1,0.0,0.0); - delta[ordering[pose2SLAM::PoseKey(2)]] = Vector_(3, 0.0,0.1,0.0); - delta[ordering[pose2SLAM::PoseKey(3)]] = Vector_(3, 0.1,0.0,0.0); + delta[ordering[0]] = Vector_(3, 0.0,-0.1,0.0); + delta[ordering[1]] = Vector_(3, -0.1,0.0,0.0); + delta[ordering[2]] = Vector_(3, 0.0,0.1,0.0); + delta[ordering[3]] = Vector_(3, 0.1,0.0,0.0); pose2SLAM::Values actual = circle.retract(delta, ordering); CHECK(assert_equal(expected,actual)); } @@ -390,15 +397,15 @@ static SharedNoiseModel sigmas = sharedSigmas(Vector_(3,sx,sy,st)); /* ************************************************************************* */ // Very simple test establishing Ax-b \approx z-h(x) -TEST( Pose2Prior, error ) +TEST_UNSAFE( Pose2Prior, error ) { // Choose a linearization point Pose2 p1(1, 0, 0); // robot at (1,0) pose2SLAM::Values x0; - x0.insert(PoseKey(1), p1); + x0.insert(1, p1); // Create factor - pose2SLAM::Prior factor(PoseKey(1), p1, sigmas); + pose2SLAM::Prior factor(1, p1, sigmas); // Actual linearization Ordering ordering(*x0.orderingArbitrary()); @@ -407,14 +414,14 @@ TEST( Pose2Prior, error ) // Check error at x0, i.e. delta = zero ! VectorValues delta(VectorValues::Zero(x0.dims(ordering))); - delta[ordering[kx1]] = zero(3); + delta[ordering[1]] = zero(3); Vector error_at_zero = Vector_(3,0.0,0.0,0.0); CHECK(assert_equal(error_at_zero,factor.whitenedError(x0))); CHECK(assert_equal(-error_at_zero,linear->error_vector(delta))); // Check error after increasing p2 VectorValues addition(VectorValues::Zero(x0.dims(ordering))); - addition[ordering[kx1]] = Vector_(3, 0.1, 0.0, 0.0); + addition[ordering[1]] = Vector_(3, 0.1, 0.0, 0.0); VectorValues plus = delta + addition; pose2SLAM::Values x1 = x0.retract(plus, ordering); Vector error_at_plus = Vector_(3,0.1/sx,0.0,0.0); // h(x)-z = 0.1 ! @@ -424,8 +431,8 @@ TEST( Pose2Prior, error ) /* ************************************************************************* */ // common Pose2Prior for tests below -static gtsam::Pose2 priorVal(2,2,M_PI/2.0); -static pose2SLAM::Prior priorFactor(PoseKey(1), priorVal, sigmas); +static gtsam::Pose2 priorVal(2,2,M_PI_2); +static pose2SLAM::Prior priorFactor(1, priorVal, sigmas); /* ************************************************************************* */ // The error |A*dx-b| approximates (h(x0+dx)-z) = -error_vector @@ -435,7 +442,7 @@ LieVector hprior(const Pose2& p1) { } /* ************************************************************************* */ -TEST( Pose2Prior, linearize ) +TEST_UNSAFE( Pose2Prior, linearize ) { // Choose a linearization point at ground truth pose2SLAM::Values x0; @@ -448,12 +455,12 @@ TEST( Pose2Prior, linearize ) // Test with numerical derivative Matrix numericalH = numericalDerivative11(hprior, priorVal); - CHECK(assert_equal(numericalH,actual->getA(actual->find(ordering[kx1])))); + CHECK(assert_equal(numericalH,actual->getA(actual->find(ordering[1])))); } /* ************************************************************************* */ // Very simple test establishing Ax-b \approx z-h(x) -TEST( Pose2Factor, error ) +TEST_UNSAFE( Pose2Factor, error ) { // Choose a linearization point Pose2 p1; // robot at origin @@ -464,7 +471,7 @@ TEST( Pose2Factor, error ) // Create factor Pose2 z = p1.between(p2); - Pose2Factor factor(PoseKey(1), PoseKey(2), z, covariance); + Pose2Factor factor(1, 2, z, covariance); // Actual linearization Ordering ordering(*x0.orderingArbitrary()); @@ -473,15 +480,15 @@ TEST( Pose2Factor, error ) // Check error at x0, i.e. delta = zero ! VectorValues delta(x0.dims(ordering)); - delta[ordering[kx1]] = zero(3); - delta[ordering[kx2]] = zero(3); + delta[ordering[1]] = zero(3); + delta[ordering[2]] = zero(3); Vector error_at_zero = Vector_(3,0.0,0.0,0.0); CHECK(assert_equal(error_at_zero,factor.unwhitenedError(x0))); CHECK(assert_equal(-error_at_zero, linear->error_vector(delta))); // Check error after increasing p2 VectorValues plus = delta; - plus[ordering[kx2]] = Vector_(3, 0.1, 0.0, 0.0); + plus[ordering[2]] = Vector_(3, 0.1, 0.0, 0.0); pose2SLAM::Values x1 = x0.retract(plus, ordering); Vector error_at_plus = Vector_(3,0.1/sx,0.0,0.0); // h(x)-z = 0.1 ! CHECK(assert_equal(error_at_plus,factor.whitenedError(x1))); @@ -490,18 +497,18 @@ TEST( Pose2Factor, error ) /* ************************************************************************* */ // common Pose2Factor for tests below -static Pose2 measured(2,2,M_PI/2.0); -static Pose2Factor factor(PoseKey(1),PoseKey(2),measured, covariance); +static Pose2 measured(2,2,M_PI_2); +static Pose2Factor factor(1,2,measured, covariance); /* ************************************************************************* */ -TEST( Pose2Factor, rhs ) +TEST_UNSAFE( Pose2Factor, rhs ) { // Choose a linearization point - Pose2 p1(1.1,2,M_PI/2.0); // robot at (1.1,2) looking towards y (ground truth is at 1,2, see testPose2) + Pose2 p1(1.1,2,M_PI_2); // robot at (1.1,2) looking towards y (ground truth is at 1,2, see testPose2) Pose2 p2(-1,4.1,M_PI); // robot at (-1,4.1) looking at negative (ground truth is at -1,4) pose2SLAM::Values x0; - x0.insert(pose2SLAM::PoseKey(1),p1); - x0.insert(pose2SLAM::PoseKey(2),p2); + x0.insert(1,p1); + x0.insert(2,p2); // Actual linearization Ordering ordering(*x0.orderingArbitrary()); @@ -510,7 +517,7 @@ TEST( Pose2Factor, rhs ) // Check RHS Pose2 hx0 = p1.between(p2); - CHECK(assert_equal(Pose2(2.1, 2.1, M_PI/2.0),hx0)); + CHECK(assert_equal(Pose2(2.1, 2.1, M_PI_2),hx0)); Vector expected_b = Vector_(3, -0.1/sx, 0.1/sy, 0.0); CHECK(assert_equal(expected_b,-factor.whitenedError(x0))); CHECK(assert_equal(expected_b,linear->getb())); @@ -524,14 +531,14 @@ LieVector h(const Pose2& p1,const Pose2& p2) { } /* ************************************************************************* */ -TEST( Pose2Factor, linearize ) +TEST_UNSAFE( Pose2Factor, linearize ) { // Choose a linearization point at ground truth - Pose2 p1(1,2,M_PI/2.0); + Pose2 p1(1,2,M_PI_2); Pose2 p2(-1,4,M_PI); pose2SLAM::Values x0; - x0.insert(pose2SLAM::PoseKey(1),p1); - x0.insert(pose2SLAM::PoseKey(2),p2); + x0.insert(1,p1); + x0.insert(2,p2); // expected linearization Matrix expectedH1 = covariance->Whiten(Matrix_(3,3, @@ -549,7 +556,7 @@ TEST( Pose2Factor, linearize ) // expected linear factor Ordering ordering(*x0.orderingArbitrary()); SharedDiagonal probModel1 = noiseModel::Unit::Create(3); - JacobianFactor expected(ordering[kx1], expectedH1, ordering[kx2], expectedH2, expected_b, probModel1); + JacobianFactor expected(ordering[1], expectedH1, ordering[2], expectedH2, expected_b, probModel1); // Actual linearization boost::shared_ptr actual = diff --git a/gtsam/slam/tests/testPose3SLAM.cpp b/gtsam/slam/tests/testPose3SLAM.cpp index d4ab3afdb..46a1c35c5 100644 --- a/gtsam/slam/tests/testPose3SLAM.cpp +++ b/gtsam/slam/tests/testPose3SLAM.cpp @@ -10,47 +10,41 @@ * -------------------------------------------------------------------------- */ /** - * @file testPose3Graph.cpp - * @author Frank Dellaert, Viorela Ila + * @file testpose3SLAM.cpp + * @author Frank Dellaert + * @author Viorela Ila **/ -#include +#include +#include +#include + +#include -#include #include #include #include using namespace boost; using namespace boost::assign; -#include - -// TODO: DANGEROUS, create shared pointers -#define GTSAM_MAGIC_GAUSSIAN 6 - -#include -#include -#include +#include using namespace std; using namespace gtsam; -using namespace pose3SLAM; // common measurement covariance -static Matrix covariance = eye(6); +static noiseModel::Gaussian::shared_ptr covariance(noiseModel::Unit::Create(6)); const double tol=1e-5; -const Key kx0 = Symbol('x',0), kx1 = Symbol('x',1), kx2 = Symbol('x',2), kx3 = Symbol('x',3), kx4 = Symbol('x',4), kx5 = Symbol('x',5); - /* ************************************************************************* */ // test optimization with 6 poses arranged in a hexagon and a loop closure TEST(Pose3Graph, optimizeCircle) { // Create a hexagon of poses double radius = 10; - Values hexagon = pose3SLAM::circle(6,radius); - Pose3 gT0 = hexagon.at(PoseKey(0)), gT1 = hexagon.at(PoseKey(1)); + Values hexagon = pose3SLAM::Values::Circle(6,radius); + Pose3 gT0 = hexagon.at(0), gT1 = hexagon.at(1); // create a Pose graph with one equality constraint and one measurement pose3SLAM::Graph fg; @@ -67,16 +61,16 @@ TEST(Pose3Graph, optimizeCircle) { // Create initial config Values initial; - initial.insert(PoseKey(0), gT0); - initial.insert(PoseKey(1), hexagon.at(PoseKey(1)).retract(Vector_(6,-0.1, 0.1,-0.1,-0.1, 0.1,-0.1))); - initial.insert(PoseKey(2), hexagon.at(PoseKey(2)).retract(Vector_(6, 0.1,-0.1, 0.1, 0.1,-0.1, 0.1))); - initial.insert(PoseKey(3), hexagon.at(PoseKey(3)).retract(Vector_(6,-0.1, 0.1,-0.1,-0.1, 0.1,-0.1))); - initial.insert(PoseKey(4), hexagon.at(PoseKey(4)).retract(Vector_(6, 0.1,-0.1, 0.1, 0.1,-0.1, 0.1))); - initial.insert(PoseKey(5), hexagon.at(PoseKey(5)).retract(Vector_(6,-0.1, 0.1,-0.1,-0.1, 0.1,-0.1))); + initial.insert(0, gT0); + initial.insert(1, hexagon.at(1).retract(Vector_(6,-0.1, 0.1,-0.1,-0.1, 0.1,-0.1))); + initial.insert(2, hexagon.at(2).retract(Vector_(6, 0.1,-0.1, 0.1, 0.1,-0.1, 0.1))); + initial.insert(3, hexagon.at(3).retract(Vector_(6,-0.1, 0.1,-0.1,-0.1, 0.1,-0.1))); + initial.insert(4, hexagon.at(4).retract(Vector_(6, 0.1,-0.1, 0.1, 0.1,-0.1, 0.1))); + initial.insert(5, hexagon.at(5).retract(Vector_(6,-0.1, 0.1,-0.1,-0.1, 0.1,-0.1))); // Choose an ordering and optimize Ordering ordering; - ordering += kx0,kx1,kx2,kx3,kx4,kx5; + ordering += 0,1,2,3,4,5; Values actual = LevenbergMarquardtOptimizer(fg, initial, ordering).optimize(); @@ -84,7 +78,7 @@ TEST(Pose3Graph, optimizeCircle) { CHECK(assert_equal(hexagon, actual,1e-4)); // Check loop closure - CHECK(assert_equal(_0T1, actual.at(PoseKey(5)).between(actual.at(PoseKey(0))),1e-5)); + CHECK(assert_equal(_0T1, actual.at(5).between(actual.at(0)),1e-5)); } /* ************************************************************************* */ @@ -94,11 +88,10 @@ TEST(Pose3Graph, partial_prior_height) { // reference: Pose3 Expmap - (0-2: Rot3) (3-5: Point3) // height prior - single element interface - Symbol key = PoseKey(1); double exp_height = 5.0; SharedDiagonal model = noiseModel::Unit::Create(1); Pose3 init(Rot3(), Point3(1.0, 2.0, 3.0)), expected(Rot3(), Point3(1.0, 2.0, exp_height)); - Partial height(key, 5, exp_height, model); + Partial height(1, 5, exp_height, model); Matrix actA; EXPECT(assert_equal(Vector_(1,-2.0), height.evaluateError(init, actA), tol)); Matrix expA = Matrix_(1, 6, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0); @@ -108,13 +101,13 @@ TEST(Pose3Graph, partial_prior_height) { graph.add(height); Values values; - values.insert(key, init); + values.insert(1, init); // linearization EXPECT_DOUBLES_EQUAL(2.0, height.error(values), tol); Values actual = LevenbergMarquardtOptimizer(graph, values).optimize(); - EXPECT(assert_equal(expected, actual.at(key), tol)); + EXPECT(assert_equal(expected, actual.at(1), tol)); EXPECT_DOUBLES_EQUAL(0.0, graph.error(actual), tol); } @@ -128,12 +121,12 @@ TEST( Pose3Factor, error ) // Create factor SharedNoiseModel I6(noiseModel::Unit::Create(6)); - pose3SLAM::Constraint factor(PoseKey(1), PoseKey(2), z, I6); + pose3SLAM::Constraint factor(1, 2, z, I6); // Create config Values x; - x.insert(PoseKey(1),t1); - x.insert(PoseKey(2),t2); + x.insert(1,t1); + x.insert(2,t2); // Get error h(x)-z -> localCoordinates(z,h(x)) = localCoordinates(z,between(t1,t2)) Vector actual = factor.unwhitenedError(x); @@ -146,12 +139,11 @@ TEST(Pose3Graph, partial_prior_xy) { typedef PartialPriorFactor Partial; // XY prior - full mask interface - Symbol key = PoseKey(1); Vector exp_xy = Vector_(2, 3.0, 4.0); SharedDiagonal model = noiseModel::Unit::Create(2); Pose3 init(Rot3(), Point3(1.0,-2.0, 3.0)), expected(Rot3(), Point3(3.0, 4.0, 3.0)); vector mask; mask += 3, 4; - Partial priorXY(key, mask, exp_xy, model); + Partial priorXY(1, mask, exp_xy, model); Matrix actA; EXPECT(assert_equal(Vector_(2,-2.0,-6.0), priorXY.evaluateError(init, actA), tol)); Matrix expA = Matrix_(2, 6, @@ -163,10 +155,10 @@ TEST(Pose3Graph, partial_prior_xy) { graph.add(priorXY); Values values; - values.insert(key, init); + values.insert(1, init); Values actual = LevenbergMarquardtOptimizer(graph, values).optimize(); - EXPECT(assert_equal(expected, actual.at(key), tol)); + EXPECT(assert_equal(expected, actual.at(1), tol)); EXPECT_DOUBLES_EQUAL(0.0, graph.error(actual), tol); } @@ -182,12 +174,12 @@ TEST( Values, pose3Circle ) { // expected is 4 poses tangent to circle with radius 1m Values expected; - expected.insert(PoseKey(0), Pose3(R1, Point3( 1, 0, 0))); - expected.insert(PoseKey(1), Pose3(R2, Point3( 0, 1, 0))); - expected.insert(PoseKey(2), Pose3(R3, Point3(-1, 0, 0))); - expected.insert(PoseKey(3), Pose3(R4, Point3( 0,-1, 0))); + expected.insert(0, Pose3(R1, Point3( 1, 0, 0))); + expected.insert(1, Pose3(R2, Point3( 0, 1, 0))); + expected.insert(2, Pose3(R3, Point3(-1, 0, 0))); + expected.insert(3, Pose3(R4, Point3( 0,-1, 0))); - Values actual = pose3SLAM::circle(4,1.0); + Values actual = pose3SLAM::Values::Circle(4,1.0); CHECK(assert_equal(expected,actual)); } @@ -195,10 +187,10 @@ TEST( Values, pose3Circle ) TEST( Values, expmap ) { Values expected; - expected.insert(PoseKey(0), Pose3(R1, Point3( 1.0, 0.1, 0))); - expected.insert(PoseKey(1), Pose3(R2, Point3(-0.1, 1.0, 0))); - expected.insert(PoseKey(2), Pose3(R3, Point3(-1.0,-0.1, 0))); - expected.insert(PoseKey(3), Pose3(R4, Point3( 0.1,-1.0, 0))); + expected.insert(0, Pose3(R1, Point3( 1.0, 0.1, 0))); + expected.insert(1, Pose3(R2, Point3(-0.1, 1.0, 0))); + expected.insert(2, Pose3(R3, Point3(-1.0,-0.1, 0))); + expected.insert(3, Pose3(R4, Point3( 0.1,-1.0, 0))); Ordering ordering(*expected.orderingArbitrary()); VectorValues delta(expected.dims(ordering)); @@ -207,7 +199,7 @@ TEST( Values, expmap ) 0.0,0.0,0.0, 0.1, 0.0, 0.0, 0.0,0.0,0.0, 0.1, 0.0, 0.0, 0.0,0.0,0.0, 0.1, 0.0, 0.0); - Values actual = pose3SLAM::circle(4,1.0).retract(delta, ordering); + Values actual = pose3SLAM::Values::Circle(4,1.0).retract(delta, ordering); CHECK(assert_equal(expected,actual)); } diff --git a/gtsam/slam/tests/testProjectionFactor.cpp b/gtsam/slam/tests/testProjectionFactor.cpp index 8b4ecbf21..0cd357c70 100644 --- a/gtsam/slam/tests/testProjectionFactor.cpp +++ b/gtsam/slam/tests/testProjectionFactor.cpp @@ -16,13 +16,12 @@ * @date Nov 2009 */ -#include - #include +#include +#include using namespace std; using namespace gtsam; -using namespace visualSLAM; // make cube static Point3 @@ -37,23 +36,23 @@ static Cal3_S2 K(fov,w,h); static SharedNoiseModel sigma(noiseModel::Unit::Create(1)); static shared_ptrK sK(new Cal3_S2(K)); -const Key kx1 = Symbol('x',1), kl1 = Symbol('l',1); - -// make cameras +// Convenience for named keys +using symbol_shorthand::X; +using symbol_shorthand::L; /* ************************************************************************* */ TEST( ProjectionFactor, error ) { // Create the factor with a measurement that is 3 pixels off in x Point2 z(323.,240.); - int cameraFrameNumber=1, landmarkNumber=1; + int i=1, j=1; boost::shared_ptr - factor(new visualSLAM::ProjectionFactor(z, sigma, PoseKey(cameraFrameNumber), PointKey(landmarkNumber), sK)); + factor(new visualSLAM::ProjectionFactor(z, sigma, X(i), L(j), sK)); // For the following values structure, the factor predicts 320,240 Values config; - Rot3 R;Point3 t1(0,0,-6); Pose3 x1(R,t1); config.insert(PoseKey(1), x1); - Point3 l1; config.insert(PointKey(1), l1); + Rot3 R;Point3 t1(0,0,-6); Pose3 x1(R,t1); config.insert(X(1), x1); + Point3 l1; config.insert(L(1), l1); // Point should project to Point2(320.,240.) CHECK(assert_equal(Vector_(2, -3.0, 0.0), factor->unwhitenedError(config))); @@ -61,12 +60,12 @@ TEST( ProjectionFactor, error ) DOUBLES_EQUAL(4.5,factor->error(config),1e-9); // Check linearize - Ordering ordering; ordering += kx1,kl1; + Ordering ordering; ordering += X(1),L(1); Matrix Ax1 = Matrix_(2, 6, 0., -554.256, 0., -92.376, 0., 0., 554.256, 0., 0., 0., -92.376, 0.); Matrix Al1 = Matrix_(2, 3, 92.376, 0., 0., 0., 92.376, 0.); Vector b = Vector_(2,3.,0.); SharedDiagonal probModel1 = noiseModel::Unit::Create(2); - JacobianFactor expected(ordering[kx1], Ax1, ordering[kl1], Al1, b, probModel1); + JacobianFactor expected(ordering[X(1)], Ax1, ordering[L(1)], Al1, b, probModel1); JacobianFactor::shared_ptr actual = boost::dynamic_pointer_cast(factor->linearize(config, ordering)); CHECK(assert_equal(expected,*actual,1e-3)); @@ -81,11 +80,11 @@ TEST( ProjectionFactor, error ) // expmap on a config Values expected_config; - Point3 t2(1,1,-5); Pose3 x2(R,t2); expected_config.insert(PoseKey(1), x2); - Point3 l2(1,2,3); expected_config.insert(PointKey(1), l2); + Point3 t2(1,1,-5); Pose3 x2(R,t2); expected_config.insert(X(1), x2); + Point3 l2(1,2,3); expected_config.insert(L(1), l2); VectorValues delta(expected_config.dims(ordering)); - delta[ordering[kx1]] = Vector_(6, 0.,0.,0., 1.,1.,1.); - delta[ordering[kl1]] = Vector_(3, 1.,2.,3.); + delta[ordering[X(1)]] = Vector_(6, 0.,0.,0., 1.,1.,1.); + delta[ordering[L(1)]] = Vector_(3, 1.,2.,3.); Values actual_config = config.retract(delta, ordering); CHECK(assert_equal(expected_config,actual_config,1e-9)); } @@ -95,12 +94,12 @@ TEST( ProjectionFactor, equals ) { // Create two identical factors and make sure they're equal Vector z = Vector_(2,323.,240.); - int cameraFrameNumber=1, landmarkNumber=1; + int i=1, j=1; boost::shared_ptr - factor1(new visualSLAM::ProjectionFactor(z, sigma, PoseKey(cameraFrameNumber), PointKey(landmarkNumber), sK)); + factor1(new visualSLAM::ProjectionFactor(z, sigma, X(i), L(j), sK)); boost::shared_ptr - factor2(new visualSLAM::ProjectionFactor(z, sigma, PoseKey(cameraFrameNumber), PointKey(landmarkNumber), sK)); + factor2(new visualSLAM::ProjectionFactor(z, sigma, X(i), L(j), sK)); CHECK(assert_equal(*factor1, *factor2)); } diff --git a/gtsam/slam/tests/testSerializationSLAM.cpp b/gtsam/slam/tests/testSerializationSLAM.cpp index 9cfb8bb72..275abe1b8 100644 --- a/gtsam/slam/tests/testSerializationSLAM.cpp +++ b/gtsam/slam/tests/testSerializationSLAM.cpp @@ -11,17 +11,17 @@ /** * @file testSerializationSLAM.cpp - * @brief + * @brief test serialization * @author Richard Roberts * @date Feb 7, 2012 */ -#include -#include #include #include #include - +#include +#include +#include #include #include @@ -29,6 +29,10 @@ using namespace std; using namespace gtsam; using namespace gtsam::serializationTestHelpers; +// Convenience for named keys +using symbol_shorthand::X; +using symbol_shorthand::L; + /* Create GUIDs for factors */ /* ************************************************************************* */ BOOST_CLASS_EXPORT_GUID(gtsam::JacobianFactor, "gtsam::JacobianFactor"); @@ -49,7 +53,7 @@ BOOST_CLASS_EXPORT_GUID(gtsam::SharedDiagonal, "gtsam_SharedDiagonal"); TEST (Serialization, smallExample_linear) { using namespace example; - Ordering ordering; ordering += Symbol('x',1),Symbol('x',2),Symbol('l',1); + Ordering ordering; ordering += X(1),X(2),L(1); GaussianFactorGraph fg = createGaussianFactorGraph(ordering); EXPECT(equalsObj(ordering)); EXPECT(equalsXML(ordering)); @@ -109,19 +113,20 @@ BOOST_CLASS_EXPORT(gtsam::Pose2) TEST (Serialization, planar_system) { using namespace planarSLAM; planarSLAM::Values values; - values.insert(PointKey(3), Point2(1.0, 2.0)); - values.insert(PoseKey(4), Pose2(1.0, 2.0, 0.3)); + Symbol i2('x',2), i3('x',3), i4('x',4), i9('x',9), j3('l',3), j5('l',5), j9('l',9); + values.insert(j3, Point2(1.0, 2.0)); + values.insert(i4, Pose2(1.0, 2.0, 0.3)); SharedNoiseModel model1 = noiseModel::Isotropic::Sigma(1, 0.3); SharedNoiseModel model2 = noiseModel::Isotropic::Sigma(2, 0.3); SharedNoiseModel model3 = noiseModel::Isotropic::Sigma(3, 0.3); - Prior prior(PoseKey(3), Pose2(0.1,-0.3, 0.2), model1); - Bearing bearing(PoseKey(3), PointKey(5), Rot2::fromDegrees(0.5), model1); - Range range(PoseKey(2), PointKey(9), 7.0, model1); - BearingRange bearingRange(PoseKey(2), PointKey(3), Rot2::fromDegrees(0.6), 2.0, model2); - Odometry odometry(PoseKey(2), PoseKey(3), Pose2(1.0, 2.0, 0.3), model3); - Constraint constraint(PoseKey(9), Pose2(2.0,-1.0, 0.2)); + Prior prior(i3, Pose2(0.1,-0.3, 0.2), model1); + Bearing bearing(i3, j5, Rot2::fromDegrees(0.5), model1); + Range range(i2, j9, 7.0, model1); + BearingRange bearingRange(i2, j3, Rot2::fromDegrees(0.6), 2.0, model2); + Odometry odometry(i2, i3, Pose2(1.0, 2.0, 0.3), model3); + Constraint constraint(i9, Pose2(2.0,-1.0, 0.2)); Graph graph; graph.add(prior); @@ -132,8 +137,8 @@ TEST (Serialization, planar_system) { graph.add(constraint); // text - EXPECT(equalsObj(PoseKey(2))); - EXPECT(equalsObj(PointKey(3))); + EXPECT(equalsObj(i2)); + EXPECT(equalsObj(j3)); EXPECT(equalsObj(values)); EXPECT(equalsObj(prior)); EXPECT(equalsObj(bearing)); @@ -144,8 +149,8 @@ TEST (Serialization, planar_system) { EXPECT(equalsObj(graph)); // xml - EXPECT(equalsXML(PoseKey(2))); - EXPECT(equalsXML(PointKey(3))); + EXPECT(equalsXML(i2)); + EXPECT(equalsXML(j3)); EXPECT(equalsXML(values)); EXPECT(equalsXML(prior)); EXPECT(equalsXML(bearing)); @@ -176,7 +181,7 @@ Cal3_S2 cal1(1.0, 2.0, 0.3, 0.1, 0.5); /* ************************************************************************* */ TEST (Serialization, visual_system) { using namespace visualSLAM; - Values values; + visualSLAM::Values values; Symbol x1('x',1), x2('x',2); Symbol l1('l',1), l2('l',2); Pose3 pose1 = pose3, pose2 = pose3.inverse(); @@ -189,11 +194,11 @@ TEST (Serialization, visual_system) { boost::shared_ptr K(new Cal3_S2(cal1)); Graph graph; - graph.addMeasurement(Point2(1.0, 2.0), model2, 1, 1, K); - graph.addPointConstraint(1, pt1); - graph.addPointPrior(1, pt2, model3); - graph.addPoseConstraint(1, pose1); - graph.addPosePrior(1, pose2, model6); + graph.addMeasurement(Point2(1.0, 2.0), model2, x1, l1, K); + graph.addPointConstraint(l1, pt1); + graph.addPointPrior(l1, pt2, model3); + graph.addPoseConstraint(x1, pose1); + graph.addPosePrior(x1, pose2, model6); EXPECT(equalsObj(values)); EXPECT(equalsObj(graph)); diff --git a/gtsam/slam/tests/testSimulated2D.cpp b/gtsam/slam/tests/testSimulated2D.cpp index 3513927a7..b72a8f4c0 100644 --- a/gtsam/slam/tests/testSimulated2D.cpp +++ b/gtsam/slam/tests/testSimulated2D.cpp @@ -31,8 +31,8 @@ using namespace simulated2D; TEST( simulated2D, Simulated2DValues ) { simulated2D::Values actual; - actual.insert(simulated2D::PoseKey(1),Point2(1,1)); - actual.insert(simulated2D::PointKey(2),Point2(2,2)); + actual.insert(1,Point2(1,1)); + actual.insert(2,Point2(2,2)); EXPECT(assert_equal(actual,actual,1e-9)); } diff --git a/gtsam/slam/tests/testSimulated2DOriented.cpp b/gtsam/slam/tests/testSimulated2DOriented.cpp index 64844cb2a..d017512ce 100644 --- a/gtsam/slam/tests/testSimulated2DOriented.cpp +++ b/gtsam/slam/tests/testSimulated2DOriented.cpp @@ -16,17 +16,21 @@ * @brief unit tests for simulated2DOriented */ -#include -#include - -#include -#include #include #include +#include +#include +#include using namespace std; using namespace gtsam; -using namespace simulated2DOriented; + +#include +#include + +// Convenience for named keys +using symbol_shorthand::X; +using symbol_shorthand::L; /* ************************************************************************* */ TEST( simulated2DOriented, Dprior ) @@ -55,11 +59,11 @@ TEST( simulated2DOriented, constructor ) { Pose2 measurement(0.2, 0.3, 0.1); SharedDiagonal model(Vector_(3, 1., 1., 1.)); - simulated2DOriented::Odometry factor(measurement, model, simulated2DOriented::PoseKey(1), simulated2DOriented::PoseKey(2)); + simulated2DOriented::Odometry factor(measurement, model, X(1), X(2)); simulated2DOriented::Values config; - config.insert(simulated2DOriented::PoseKey(1), Pose2(1., 0., 0.2)); - config.insert(simulated2DOriented::PoseKey(2), Pose2(2., 0., 0.1)); + config.insert(X(1), Pose2(1., 0., 0.2)); + config.insert(X(2), Pose2(2., 0., 0.1)); boost::shared_ptr lf = factor.linearize(config, *config.orderingArbitrary()); } diff --git a/gtsam/slam/tests/testStereoFactor.cpp b/gtsam/slam/tests/testStereoFactor.cpp index 25cd6e16f..35ef081bc 100644 --- a/gtsam/slam/tests/testStereoFactor.cpp +++ b/gtsam/slam/tests/testStereoFactor.cpp @@ -12,24 +12,21 @@ /** * @file testStereoFactor.cpp * @brief Unit test for StereoFactor - * single camera * @author Chris Beall */ -#include - -#include -#include +#include +#include #include #include -#include +#include +#include +#include -#include +#include using namespace std; using namespace gtsam; -using namespace boost; -using namespace visualSLAM; Pose3 camera1(Matrix_(3,3, 1., 0., 0., @@ -45,6 +42,10 @@ StereoCamera stereoCam(Pose3(), K); Point3 p(0, 0, 5); static SharedNoiseModel sigma(noiseModel::Unit::Create(1)); +// Convenience for named keys +using symbol_shorthand::X; +using symbol_shorthand::L; + /* ************************************************************************* */ TEST( StereoFactor, singlePoint) { @@ -52,18 +53,18 @@ TEST( StereoFactor, singlePoint) boost::shared_ptr K(new Cal3_S2Stereo(625, 625, 0, 320, 240, 0.5)); NonlinearFactorGraph graph; - graph.add(visualSLAM::PoseConstraint(PoseKey(1),camera1)); + graph.add(visualSLAM::PoseConstraint(X(1),camera1)); StereoPoint2 z14(320,320.0-50, 240); // arguments: measurement, sigma, cam#, measurement #, K, baseline (m) - graph.add(visualSLAM::StereoFactor(z14,sigma, PoseKey(1), PointKey(1), K)); + graph.add(visualSLAM::StereoFactor(z14,sigma, X(1), L(1), K)); // Create a configuration corresponding to the ground truth Values values; - values.insert(PoseKey(1), camera1); // add camera at z=6.25m looking towards origin + values.insert(X(1), camera1); // add camera at z=6.25m looking towards origin Point3 l1(0, 0, 0); - values.insert(PointKey(1), l1); // add point at origin; + values.insert(L(1), l1); // add point at origin; GaussNewtonOptimizer optimizer(graph, values); diff --git a/gtsam/slam/tests/testVSLAM.cpp b/gtsam/slam/tests/testVisualSLAM.cpp similarity index 65% rename from gtsam/slam/tests/testVSLAM.cpp rename to gtsam/slam/tests/testVisualSLAM.cpp index bb7623954..f09d5117a 100644 --- a/gtsam/slam/tests/testVSLAM.cpp +++ b/gtsam/slam/tests/testVisualSLAM.cpp @@ -10,43 +10,46 @@ * -------------------------------------------------------------------------- */ /** - * @file testGraph.cpp - * @brief Unit test for two cameras and four landmarks - * single camera + * @file testVisualSLAM.cpp + * @brief Unit test for two cameras and four landmarks, single camera * @author Chris Beall * @author Frank Dellaert * @author Viorela Ila */ +#include +#include +#include +#include + #include #include using namespace boost; -#include -#include -#include - using namespace std; using namespace gtsam; -using namespace boost; -using namespace visualSLAM; + +/* ************************************************************************* */ static SharedNoiseModel sigma(noiseModel::Unit::Create(1)); -/* ************************************************************************* */ -Point3 landmark1(-1.0,-1.0, 0.0); -Point3 landmark2(-1.0, 1.0, 0.0); -Point3 landmark3( 1.0, 1.0, 0.0); -Point3 landmark4( 1.0,-1.0, 0.0); +// Convenience for named keys +using symbol_shorthand::X; +using symbol_shorthand::L; -Pose3 camera1(Matrix_(3,3, +static Point3 landmark1(-1.0,-1.0, 0.0); +static Point3 landmark2(-1.0, 1.0, 0.0); +static Point3 landmark3( 1.0, 1.0, 0.0); +static Point3 landmark4( 1.0,-1.0, 0.0); + +static Pose3 camera1(Matrix_(3,3, 1., 0., 0., 0.,-1., 0., 0., 0.,-1. ), Point3(0,0,6.25)); -Pose3 camera2(Matrix_(3,3, +static Pose3 camera2(Matrix_(3,3, 1., 0., 0., 0.,-1., 0., 0., 0.,-1. @@ -66,14 +69,14 @@ visualSLAM::Graph testGraph() { shared_ptrK sK(new Cal3_S2(625, 625, 0, 0, 0)); visualSLAM::Graph g; - g.addMeasurement(z11, sigma, 1, 1, sK); - g.addMeasurement(z12, sigma, 1, 2, sK); - g.addMeasurement(z13, sigma, 1, 3, sK); - g.addMeasurement(z14, sigma, 1, 4, sK); - g.addMeasurement(z21, sigma, 2, 1, sK); - g.addMeasurement(z22, sigma, 2, 2, sK); - g.addMeasurement(z23, sigma, 2, 3, sK); - g.addMeasurement(z24, sigma, 2, 4, sK); + g.addMeasurement(z11, sigma, X(1), L(1), sK); + g.addMeasurement(z12, sigma, X(1), L(2), sK); + g.addMeasurement(z13, sigma, X(1), L(3), sK); + g.addMeasurement(z14, sigma, X(1), L(4), sK); + g.addMeasurement(z21, sigma, X(2), L(1), sK); + g.addMeasurement(z22, sigma, X(2), L(2), sK); + g.addMeasurement(z23, sigma, X(2), L(3), sK); + g.addMeasurement(z24, sigma, X(2), L(4), sK); return g; } @@ -83,22 +86,22 @@ TEST( Graph, optimizeLM) // build a graph visualSLAM::Graph graph(testGraph()); // add 3 landmark constraints - graph.addPointConstraint(1, landmark1); - graph.addPointConstraint(2, landmark2); - graph.addPointConstraint(3, landmark3); + graph.addPointConstraint(L(1), landmark1); + graph.addPointConstraint(L(2), landmark2); + graph.addPointConstraint(L(3), landmark3); // Create an initial values structure corresponding to the ground truth Values initialEstimate; - initialEstimate.insert(PoseKey(1), camera1); - initialEstimate.insert(PoseKey(2), camera2); - initialEstimate.insert(PointKey(1), landmark1); - initialEstimate.insert(PointKey(2), landmark2); - initialEstimate.insert(PointKey(3), landmark3); - initialEstimate.insert(PointKey(4), landmark4); + initialEstimate.insert(X(1), camera1); + initialEstimate.insert(X(2), camera2); + initialEstimate.insert(L(1), landmark1); + initialEstimate.insert(L(2), landmark2); + initialEstimate.insert(L(3), landmark3); + initialEstimate.insert(L(4), landmark4); // Create an ordering of the variables Ordering ordering; - ordering += PointKey(1),PointKey(2),PointKey(3),PointKey(4),PoseKey(1),PoseKey(2); + ordering += L(1),L(2),L(3),L(4),X(1),X(2); // Create an optimizer and check its error // We expect the initial to be zero because config is the ground truth @@ -121,21 +124,21 @@ TEST( Graph, optimizeLM2) // build a graph visualSLAM::Graph graph(testGraph()); // add 2 camera constraints - graph.addPoseConstraint(1, camera1); - graph.addPoseConstraint(2, camera2); + graph.addPoseConstraint(X(1), camera1); + graph.addPoseConstraint(X(2), camera2); // Create an initial values structure corresponding to the ground truth Values initialEstimate; - initialEstimate.insert(PoseKey(1), camera1); - initialEstimate.insert(PoseKey(2), camera2); - initialEstimate.insert(PointKey(1), landmark1); - initialEstimate.insert(PointKey(2), landmark2); - initialEstimate.insert(PointKey(3), landmark3); - initialEstimate.insert(PointKey(4), landmark4); + initialEstimate.insert(X(1), camera1); + initialEstimate.insert(X(2), camera2); + initialEstimate.insert(L(1), landmark1); + initialEstimate.insert(L(2), landmark2); + initialEstimate.insert(L(3), landmark3); + initialEstimate.insert(L(4), landmark4); // Create an ordering of the variables Ordering ordering; - ordering += PointKey(1),PointKey(2),PointKey(3),PointKey(4),PoseKey(1),PoseKey(2); + ordering += L(1),L(2),L(3),L(4),X(1),X(2); // Create an optimizer and check its error // We expect the initial to be zero because config is the ground truth @@ -158,17 +161,17 @@ TEST( Graph, CHECK_ORDERING) // build a graph visualSLAM::Graph graph = testGraph(); // add 2 camera constraints - graph.addPoseConstraint(1, camera1); - graph.addPoseConstraint(2, camera2); + graph.addPoseConstraint(X(1), camera1); + graph.addPoseConstraint(X(2), camera2); // Create an initial values structure corresponding to the ground truth Values initialEstimate; - initialEstimate.insert(PoseKey(1), camera1); - initialEstimate.insert(PoseKey(2), camera2); - initialEstimate.insert(PointKey(1), landmark1); - initialEstimate.insert(PointKey(2), landmark2); - initialEstimate.insert(PointKey(3), landmark3); - initialEstimate.insert(PointKey(4), landmark4); + initialEstimate.insert(X(1), camera1); + initialEstimate.insert(X(2), camera2); + initialEstimate.insert(L(1), landmark1); + initialEstimate.insert(L(2), landmark2); + initialEstimate.insert(L(3), landmark3); + initialEstimate.insert(L(4), landmark4); // Create an optimizer and check its error // We expect the initial to be zero because config is the ground truth @@ -189,21 +192,21 @@ TEST( Values, update_with_large_delta) { // this test ensures that if the update for delta is larger than // the size of the config, it only updates existing variables Values init; - init.insert(PoseKey(1), Pose3()); - init.insert(PointKey(1), Point3(1.0, 2.0, 3.0)); + init.insert(X(1), Pose3()); + init.insert(L(1), Point3(1.0, 2.0, 3.0)); Values expected; - expected.insert(PoseKey(1), Pose3(Rot3(), Point3(0.1, 0.1, 0.1))); - expected.insert(PointKey(1), Point3(1.1, 2.1, 3.1)); + expected.insert(X(1), Pose3(Rot3(), Point3(0.1, 0.1, 0.1))); + expected.insert(L(1), Point3(1.1, 2.1, 3.1)); Ordering largeOrdering; Values largeValues = init; - largeValues.insert(PoseKey(2), Pose3()); - largeOrdering += PoseKey(1),PointKey(1),PoseKey(2); + largeValues.insert(X(2), Pose3()); + largeOrdering += X(1),L(1),X(2); VectorValues delta(largeValues.dims(largeOrdering)); - delta[largeOrdering[PoseKey(1)]] = Vector_(6, 0.0, 0.0, 0.0, 0.1, 0.1, 0.1); - delta[largeOrdering[PointKey(1)]] = Vector_(3, 0.1, 0.1, 0.1); - delta[largeOrdering[PoseKey(2)]] = Vector_(6, 0.0, 0.0, 0.0, 100.1, 4.1, 9.1); + delta[largeOrdering[X(1)]] = Vector_(6, 0.0, 0.0, 0.0, 0.1, 0.1, 0.1); + delta[largeOrdering[L(1)]] = Vector_(3, 0.1, 0.1, 0.1); + delta[largeOrdering[X(2)]] = Vector_(6, 0.0, 0.0, 0.0, 100.1, 4.1, 9.1); Values actual = init.retract(delta, largeOrdering); CHECK(assert_equal(expected,actual)); diff --git a/gtsam/slam/visualSLAM.cpp b/gtsam/slam/visualSLAM.cpp index bc2ee199b..f4cdb0af3 100644 --- a/gtsam/slam/visualSLAM.cpp +++ b/gtsam/slam/visualSLAM.cpp @@ -22,38 +22,45 @@ namespace visualSLAM { /* ************************************************************************* */ void Graph::addMeasurement(const Point2& measured, const SharedNoiseModel& model, - Index poseKey, Index pointKey, const shared_ptrK& K) { - boost::shared_ptr factor(new ProjectionFactor(measured, model, PoseKey(poseKey), PointKey(pointKey), K)); + Key poseKey, Key pointKey, const shared_ptrK K) { + boost::shared_ptr factor(new ProjectionFactor(measured, model, poseKey, pointKey, K)); push_back(factor); } /* ************************************************************************* */ - void Graph::addPoseConstraint(Index poseKey, const Pose3& p) { - boost::shared_ptr factor(new PoseConstraint(PoseKey(poseKey), p)); + void Graph::addStereoMeasurement(const StereoPoint2& measured, const SharedNoiseModel& model, + Key poseKey, Key pointKey, const shared_ptrKStereo K) { + boost::shared_ptr factor(new StereoFactor(measured, model, poseKey, pointKey, K)); push_back(factor); } /* ************************************************************************* */ - void Graph::addPointConstraint(Index pointKey, const Point3& p) { - boost::shared_ptr factor(new PointConstraint(PointKey(pointKey), p)); + void Graph::addPoseConstraint(Key poseKey, const Pose3& p) { + boost::shared_ptr factor(new PoseConstraint(poseKey, p)); push_back(factor); } /* ************************************************************************* */ - void Graph::addPosePrior(Index poseKey, const Pose3& p, const SharedNoiseModel& model) { - boost::shared_ptr factor(new PosePrior(PoseKey(poseKey), p, model)); + void Graph::addPointConstraint(Key pointKey, const Point3& p) { + boost::shared_ptr factor(new PointConstraint(pointKey, p)); push_back(factor); } /* ************************************************************************* */ - void Graph::addPointPrior(Index pointKey, const Point3& p, const SharedNoiseModel& model) { - boost::shared_ptr factor(new PointPrior(PointKey(pointKey), p, model)); + void Graph::addPosePrior(Key poseKey, const Pose3& p, const SharedNoiseModel& model) { + boost::shared_ptr factor(new PosePrior(poseKey, p, model)); push_back(factor); } /* ************************************************************************* */ - void Graph::addRangeFactor(Index poseKey, Index pointKey, double range, const SharedNoiseModel& model) { - push_back(boost::shared_ptr(new RangeFactor(PoseKey(poseKey), PointKey(pointKey), range, model))); + void Graph::addPointPrior(Key pointKey, const Point3& p, const SharedNoiseModel& model) { + boost::shared_ptr factor(new PointPrior(pointKey, p, model)); + push_back(factor); + } + + /* ************************************************************************* */ + void Graph::addRangeFactor(Key poseKey, Key pointKey, double range, const SharedNoiseModel& model) { + push_back(boost::shared_ptr(new RangeFactor(poseKey, pointKey, range, model))); } /* ************************************************************************* */ diff --git a/gtsam/slam/visualSLAM.h b/gtsam/slam/visualSLAM.h index 38d3312a7..f71d0c4ca 100644 --- a/gtsam/slam/visualSLAM.h +++ b/gtsam/slam/visualSLAM.h @@ -23,10 +23,10 @@ #include #include #include -#include #include #include #include +#include #include @@ -34,12 +34,6 @@ namespace visualSLAM { using namespace gtsam; - /// Convenience function for constructing a pose key - inline Symbol PoseKey(Index j) { return Symbol('x', j); } - - /// Convenience function for constructing a pose key - inline Symbol PointKey(Index j) { return Symbol('l', j); } - /** * Typedefs that make up the visualSLAM namespace. */ @@ -53,6 +47,33 @@ namespace visualSLAM { typedef GenericProjectionFactor ProjectionFactor; typedef GenericStereoFactor StereoFactor; + /// Values class, inherited from Values, mainly used as a convenience for MATLAB wrapper + struct Values: public gtsam::Values { + + typedef boost::shared_ptr shared_ptr; + + /// Default constructor + Values() {} + + /// Copy constructor + Values(const gtsam::Values& values) : + gtsam::Values(values) { + } + + /// insert a pose + void insertPose(Key i, const Pose3& pose) { insert(i, pose); } + + /// insert a point + void insertPoint(Key j, const Point3& point) { insert(j, point); } + + /// get a pose + Pose3 pose(Key i) const { return at(i); } + + /// get a point + Point3 point(Key j) const { return at(j); } + + }; + /** * Non-linear factor graph for vanilla visual SLAM */ @@ -85,21 +106,32 @@ namespace visualSLAM { * @param K shared pointer to calibration object */ void addMeasurement(const Point2& measured, const SharedNoiseModel& model, - Index poseKey, Index pointKey, const shared_ptrK& K); + Key poseKey, Key pointKey, const shared_ptrK K); + + /** + * Add a stereo factor measurement + * @param measured the measurement + * @param model the noise model for the measurement + * @param poseKey variable key for the camera pose + * @param pointKey variable key for the landmark + * @param K shared pointer to stereo calibration object + */ + void addStereoMeasurement(const StereoPoint2& measured, const SharedNoiseModel& model, + Key poseKey, Key pointKey, const shared_ptrKStereo K); /** * Add a constraint on a pose (for now, *must* be satisfied in any Values) * @param key variable key of the camera pose * @param p to which pose to constrain it to */ - void addPoseConstraint(Index poseKey, const Pose3& p = Pose3()); + void addPoseConstraint(Key poseKey, const Pose3& p = Pose3()); /** * Add a constraint on a point (for now, *must* be satisfied in any Values) * @param key variable key of the landmark * @param p point around which soft prior is defined */ - void addPointConstraint(Index pointKey, const Point3& p = Point3()); + void addPointConstraint(Key pointKey, const Point3& p = Point3()); /** * Add a prior on a pose @@ -107,7 +139,7 @@ namespace visualSLAM { * @param p around which soft prior is defined * @param model uncertainty model of this prior */ - void addPosePrior(Index poseKey, const Pose3& p = Pose3(), const SharedNoiseModel& model = noiseModel::Unit::Create(6)); + void addPosePrior(Key poseKey, const Pose3& p = Pose3(), const SharedNoiseModel& model = noiseModel::Unit::Create(6)); /** * Add a prior on a landmark @@ -115,7 +147,7 @@ namespace visualSLAM { * @param p to which point to constrain it to * @param model uncertainty model of this prior */ - void addPointPrior(Index pointKey, const Point3& p = Point3(), const SharedNoiseModel& model = noiseModel::Unit::Create(3)); + void addPointPrior(Key pointKey, const Point3& p = Point3(), const SharedNoiseModel& model = noiseModel::Unit::Create(3)); /** * Add a range prior to a landmark @@ -124,7 +156,7 @@ namespace visualSLAM { * @param range approximate range to landmark * @param model uncertainty model of this prior */ - void addRangeFactor(Index poseKey, Index pointKey, double range, const SharedNoiseModel& model = noiseModel::Unit::Create(1)); + void addRangeFactor(Key poseKey, Key pointKey, double range, const SharedNoiseModel& model = noiseModel::Unit::Create(1)); /** * Optimize the graph @@ -137,6 +169,11 @@ namespace visualSLAM { return LevenbergMarquardtOptimizer(*this, initialEstimate).optimize(); } + /// Return a Marginals object + Marginals marginals(const Values& solution) const { + return Marginals(*this,solution); + } + }; // Graph } // namespaces diff --git a/gtsam_unstable/CMakeLists.txt b/gtsam_unstable/CMakeLists.txt index 9e9d66a7c..b50667f48 100644 --- a/gtsam_unstable/CMakeLists.txt +++ b/gtsam_unstable/CMakeLists.txt @@ -4,6 +4,7 @@ set (gtsam_unstable_subdirs base discrete dynamics + linear slam ) @@ -29,6 +30,7 @@ set(gtsam_unstable_srcs ${base_srcs} ${discrete_srcs} ${dynamics_srcs} + ${linear_srcs} ${slam_srcs} ) diff --git a/gtsam_unstable/discrete/tests/testPlanning.cpp b/gtsam_unstable/discrete/tests/testPlanning.cpp new file mode 100644 index 000000000..2ad1ff9ae --- /dev/null +++ b/gtsam_unstable/discrete/tests/testPlanning.cpp @@ -0,0 +1,37 @@ +/* + * testPlanning.cpp + * @brief develop code for planning example + * @date Feb 13, 2012 + * @author Frank Dellaert + */ + +//#include +#include +#include +#include +#include + +using namespace std; +using namespace gtsam; + +/* ************************************************************************* */ +TEST_UNSAFE(Planner, allInOne) +{ + // A small planning problem + // First variable is location + DiscreteKey location(0,3), + haveRock(1,2), haveSoil(2,2), haveImage(3,2), + commRock(4,2), commSoil(5,2), commImage(6,2); + + // There are 3 actions: + // Drive, communicate, sample +} + + +/* ************************************************************************* */ +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} +/* ************************************************************************* */ + diff --git a/gtsam_unstable/linear/CMakeLists.txt b/gtsam_unstable/linear/CMakeLists.txt new file mode 100644 index 000000000..d5429a5df --- /dev/null +++ b/gtsam_unstable/linear/CMakeLists.txt @@ -0,0 +1,20 @@ +# Install headers +file(GLOB base_headers "*.h") +install(FILES ${linear_headers} DESTINATION include/gtsam_unstable/linear) + +# Components to link tests in this subfolder against +set(linear_local_libs + linear + linear_unstable + base) + +set (linear_full_libs + gtsam-static + gtsam_unstable-static) + +# Exclude tests that don't work +set (base_excluded_tests "") + +# Add all tests +gtsam_add_subdir_tests(linear_unstable "${linear_local_libs}" "${linear_full_libs}" "${linear_excluded_tests}") +add_dependencies(check.unstable check.linear_unstable) diff --git a/gtsam/linear/iterative-inl.h b/gtsam_unstable/linear/iterative-inl.h similarity index 99% rename from gtsam/linear/iterative-inl.h rename to gtsam_unstable/linear/iterative-inl.h index 02048d3df..73b1e9497 100644 --- a/gtsam/linear/iterative-inl.h +++ b/gtsam_unstable/linear/iterative-inl.h @@ -18,10 +18,9 @@ #pragma once -#include - +#include #include -#include +#include using namespace std; diff --git a/gtsam/linear/iterative.cpp b/gtsam_unstable/linear/iterative.cpp similarity index 98% rename from gtsam/linear/iterative.cpp rename to gtsam_unstable/linear/iterative.cpp index c431e0c82..35b11f16d 100644 --- a/gtsam/linear/iterative.cpp +++ b/gtsam_unstable/linear/iterative.cpp @@ -15,13 +15,15 @@ * @author Frank Dellaert * @date Dec 28, 2009 */ -#include +#include #include #include #include #include -#include + + +#include using namespace std; diff --git a/gtsam/linear/iterative.h b/gtsam_unstable/linear/iterative.h similarity index 100% rename from gtsam/linear/iterative.h rename to gtsam_unstable/linear/iterative.h diff --git a/gtsam_unstable/slam/simulated3D.h b/gtsam_unstable/slam/simulated3D.h index 7b4dfce37..ef79991b8 100644 --- a/gtsam_unstable/slam/simulated3D.h +++ b/gtsam_unstable/slam/simulated3D.h @@ -23,7 +23,6 @@ #include #include #include -#include // \namespace @@ -36,12 +35,6 @@ namespace simulated3D { * the simulated2D domain. */ - /// Convenience function for constructing a pose key - inline Symbol PoseKey(Index j) { return Symbol('x', j); } - - /// Convenience function for constructing a pose key - inline Symbol PointKey(Index j) { return Symbol('l', j); } - /** * Prior on a single pose */ @@ -105,9 +98,8 @@ struct Simulated3DMeasurement: public NoiseModelFactor2 { * @param poseKey is the pose key of the robot * @param pointKey is the point key for the landmark */ - Simulated3DMeasurement(const Point3& measured, const SharedNoiseModel& model, - Key poseKey, Key pointKey) : - NoiseModelFactor2(model, poseKey, pointKey), measured_(measured) {} + Simulated3DMeasurement(const Point3& measured, const SharedNoiseModel& model, Key i, Key j) : + NoiseModelFactor2(model, i, j), measured_(measured) {} /** * Error function with optional derivatives diff --git a/gtsam_unstable/slam/tests/testSimulated3D.cpp b/gtsam_unstable/slam/tests/testSimulated3D.cpp index 50171bc76..7283544a1 100644 --- a/gtsam_unstable/slam/tests/testSimulated3D.cpp +++ b/gtsam_unstable/slam/tests/testSimulated3D.cpp @@ -15,23 +15,28 @@ * @author Alex Cunningham **/ -#include -#include - +#include +#include +#include #include #include -#include -#include + +#include + +#include using namespace gtsam; -using namespace simulated3D; + +// Convenience for named keys +using symbol_shorthand::X; +using symbol_shorthand::L; /* ************************************************************************* */ TEST( simulated3D, Values ) { Values actual; - actual.insert(simulated3D::PointKey(1),Point3(1,1,1)); - actual.insert(simulated3D::PoseKey(2),Point3(2,2,2)); + actual.insert(L(1),Point3(1,1,1)); + actual.insert(X(2),Point3(2,2,2)); EXPECT(assert_equal(actual,actual,1e-9)); } diff --git a/tests/testBoundingConstraint.cpp b/tests/testBoundingConstraint.cpp index e1b685fc8..d728742f7 100644 --- a/tests/testBoundingConstraint.cpp +++ b/tests/testBoundingConstraint.cpp @@ -15,12 +15,13 @@ * @author Alex Cunningham */ -#include - #include +#include #include #include +#include + namespace iq2D = simulated2D::inequality_constraints; using namespace std; using namespace gtsam; @@ -32,7 +33,7 @@ SharedDiagonal soft_model2_alt = noiseModel::Isotropic::Sigma(2, 0.1); SharedDiagonal hard_model1 = noiseModel::Constrained::All(1); // some simple inequality constraints -Symbol key(simulated2D::PoseKey(1)); +Symbol key('x',1); double mu = 10.0; // greater than iq2D::PoseXInequality constraint1(key, 1.0, true, mu); diff --git a/tests/testDoglegOptimizer.cpp b/tests/testDoglegOptimizer.cpp index c6241124a..529b1b2f1 100644 --- a/tests/testDoglegOptimizer.cpp +++ b/tests/testDoglegOptimizer.cpp @@ -15,15 +15,17 @@ * @author Richard Roberts */ -#include -#include -#include +#include +#include +#include +#include #include #include #include -#include -#include -#include +#include +#include + +#include #include #include // for 'list_of()' @@ -32,6 +34,10 @@ using namespace std; using namespace gtsam; +// Convenience for named keys +using symbol_shorthand::X; +using symbol_shorthand::L; + /* ************************************************************************* */ double computeError(const GaussianBayesNet& gbn, const LieVector& values) { @@ -386,11 +392,11 @@ TEST(DoglegOptimizer, Iterate) { // config far from minimum Point2 x0(3,0); boost::shared_ptr config(new Values); - config->insert(simulated2D::PoseKey(1), x0); + config->insert(X(1), x0); // ordering boost::shared_ptr ord(new Ordering()); - ord->push_back(simulated2D::PoseKey(1)); + ord->push_back(X(1)); double Delta = 1.0; for(size_t it=0; it<10; ++it) { diff --git a/tests/testExtendedKalmanFilter.cpp b/tests/testExtendedKalmanFilter.cpp index c0e5af4f7..440119e66 100644 --- a/tests/testExtendedKalmanFilter.cpp +++ b/tests/testExtendedKalmanFilter.cpp @@ -14,16 +14,21 @@ * @author Stephen Williams */ -#include - #include #include #include #include +#include #include +#include + using namespace gtsam; +// Convenience for named keys +using symbol_shorthand::X; +using symbol_shorthand::L; + /* ************************************************************************* */ TEST( ExtendedKalmanFilter, linear ) { @@ -413,11 +418,11 @@ TEST( ExtendedKalmanFilter, nonlinear ) { Point2 x_predict, x_update; for(unsigned int i = 0; i < 10; ++i){ // Create motion factor - NonlinearMotionModel motionFactor(Symbol('x',i), Symbol('x',i+1)); + NonlinearMotionModel motionFactor(X(i), X(i+1)); x_predict = ekf.predict(motionFactor); // Create a measurement factor - NonlinearMeasurementModel measurementFactor(Symbol('x',i+1), Vector_(1, z[i])); + NonlinearMeasurementModel measurementFactor(X(i+1), Vector_(1, z[i])); x_update = ekf.update(measurementFactor); EXPECT(assert_equal(expected_predict[i],x_predict, 1e-6)); diff --git a/tests/testGaussianFactor.cpp b/tests/testGaussianFactor.cpp index cb3ea18e7..cb91bc88c 100644 --- a/tests/testGaussianFactor.cpp +++ b/tests/testGaussianFactor.cpp @@ -16,7 +16,14 @@ * @author Frank Dellaert **/ -#include +#include +#include +#include +#include +#include +#include + +#include #include #include // for operator += @@ -24,24 +31,20 @@ #include // for insert using namespace boost::assign; -#include - -#include -#include -#include -#include -#include +#include using namespace std; using namespace gtsam; -using namespace example; -using namespace boost; + +// Convenience for named keys +using symbol_shorthand::X; +using symbol_shorthand::L; static SharedDiagonal sigma0_1 = sharedSigma(2,0.1), sigma_02 = sharedSigma(2,0.2), constraintModel = noiseModel::Constrained::All(2); -const Key kx1 = Symbol('x',1), kx2 = Symbol('x',2), kl1 = Symbol('l',1); +const Key kx1 = X(1), kx2 = X(2), kl1 = L(1); /* ************************************************************************* */ TEST( GaussianFactor, linearFactor ) @@ -53,7 +56,7 @@ TEST( GaussianFactor, linearFactor ) JacobianFactor expected(ordering[kx1], -10*I,ordering[kx2], 10*I, b, noiseModel::Unit::Create(2)); // create a small linear factor graph - FactorGraph fg = createGaussianFactorGraph(ordering); + FactorGraph fg = example::createGaussianFactorGraph(ordering); // get the factor kf2 from the factor graph JacobianFactor::shared_ptr lf = fg[1]; @@ -94,7 +97,7 @@ TEST( GaussianFactor, getDim ) { // get a factor Ordering ordering; ordering += kx1,kx2,kl1; - GaussianFactorGraph fg = createGaussianFactorGraph(ordering); + GaussianFactorGraph fg = example::createGaussianFactorGraph(ordering); GaussianFactor::shared_ptr factor = fg[0]; // get the size of a variable @@ -166,13 +169,13 @@ TEST( GaussianFactor, error ) { // create a small linear factor graph Ordering ordering; ordering += kx1,kx2,kl1; - GaussianFactorGraph fg = createGaussianFactorGraph(ordering); + GaussianFactorGraph fg = example::createGaussianFactorGraph(ordering); // get the first factor from the factor graph GaussianFactor::shared_ptr lf = fg[0]; // check the error of the first factor with noisy config - VectorValues cfg = createZeroDelta(ordering); + VectorValues cfg = example::createZeroDelta(ordering); // calculate the error from the factor kf1 // note the error is the same as in testNonlinearFactor @@ -226,7 +229,7 @@ TEST( GaussianFactor, matrix ) { // create a small linear factor graph Ordering ordering; ordering += kx1,kx2,kl1; - FactorGraph fg = createGaussianFactorGraph(ordering); + FactorGraph fg = example::createGaussianFactorGraph(ordering); // get the factor kf2 from the factor graph //GaussianFactor::shared_ptr lf = fg[1]; // NOTE: using the older version @@ -274,7 +277,7 @@ TEST( GaussianFactor, matrix_aug ) { // create a small linear factor graph Ordering ordering; ordering += kx1,kx2,kl1; - FactorGraph fg = createGaussianFactorGraph(ordering); + FactorGraph fg = example::createGaussianFactorGraph(ordering); // get the factor kf2 from the factor graph //GaussianFactor::shared_ptr lf = fg[1]; @@ -385,7 +388,7 @@ TEST( GaussianFactor, size ) { // create a linear factor graph Ordering ordering; ordering += kx1,kx2,kl1; - GaussianFactorGraph fg = createGaussianFactorGraph(ordering); + GaussianFactorGraph fg = example::createGaussianFactorGraph(ordering); // get some factors from the graph boost::shared_ptr factor1 = fg[0]; diff --git a/tests/testGaussianFactorGraphB.cpp b/tests/testGaussianFactorGraphB.cpp index 82e8401d6..58709328d 100644 --- a/tests/testGaussianFactorGraphB.cpp +++ b/tests/testGaussianFactorGraphB.cpp @@ -15,9 +15,16 @@ * @author Christian Potthast **/ -#include -#include -using namespace std; +#include +#include +#include +#include +#include +#include +#include +#include + +#include #include #include @@ -26,28 +33,22 @@ using namespace std; #include // for operator += using namespace boost::assign; -#include - -#include -#include -#include -#include -#include -#include -#include +#include +#include +using namespace std; using namespace gtsam; using namespace example; double tol=1e-5; -Key kx(size_t i) { return Symbol('x',i); } -Key kl(size_t i) { return Symbol('l',i); } +using symbol_shorthand::X; +using symbol_shorthand::L; /* ************************************************************************* */ TEST( GaussianFactorGraph, equals ) { - Ordering ordering; ordering += kx(1),kx(2),kl(1); + Ordering ordering; ordering += X(1),X(2),L(1); GaussianFactorGraph fg = createGaussianFactorGraph(ordering); GaussianFactorGraph fg2 = createGaussianFactorGraph(ordering); EXPECT(fg.equals(fg2)); @@ -55,7 +56,7 @@ TEST( GaussianFactorGraph, equals ) { /* ************************************************************************* */ //TEST( GaussianFactorGraph, error ) { -// Ordering ordering; ordering += kx(1),kx(2),kl(1); +// Ordering ordering; ordering += X(1),X(2),L(1); // FactorGraph fg = createGaussianFactorGraph(ordering); // VectorValues cfg = createZeroDelta(ordering); // @@ -73,10 +74,10 @@ TEST( GaussianFactorGraph, equals ) { //{ // GaussianFactorGraph fg = createGaussianFactorGraph(); // -// set separator = fg.find_separator(kx(2)); +// set separator = fg.find_separator(X(2)); // set expected; -// expected.insert(kx(1)); -// expected.insert(kl(1)); +// expected.insert(X(1)); +// expected.insert(L(1)); // // EXPECT(separator.size()==expected.size()); // set::iterator it1 = separator.begin(), it2 = expected.begin(); @@ -91,7 +92,7 @@ TEST( GaussianFactorGraph, equals ) { // GaussianFactorGraph fg = createGaussianFactorGraph(); // // // combine all factors -// GaussianFactor::shared_ptr actual = removeAndCombineFactors(fg,kx(1)); +// GaussianFactor::shared_ptr actual = removeAndCombineFactors(fg,X(1)); // // // the expected linear factor // Matrix Al1 = Matrix_(6,2, @@ -131,11 +132,11 @@ TEST( GaussianFactorGraph, equals ) { // b(5) = 1; // // vector > meas; -// meas.push_back(make_pair(kl(1), Al1)); -// meas.push_back(make_pair(kx(1), Ax1)); -// meas.push_back(make_pair(kx(2), Ax2)); +// meas.push_back(make_pair(L(1), Al1)); +// meas.push_back(make_pair(X(1), Ax1)); +// meas.push_back(make_pair(X(2), Ax2)); // GaussianFactor expected(meas, b, ones(6)); -// //GaussianFactor expected(kl(1), Al1, kx(1), Ax1, kx(2), Ax2, b); +// //GaussianFactor expected(L(1), Al1, X(1), Ax1, X(2), Ax2, b); // // // check if the two factors are the same // EXPECT(assert_equal(expected,*actual)); @@ -148,7 +149,7 @@ TEST( GaussianFactorGraph, equals ) { // GaussianFactorGraph fg = createGaussianFactorGraph(); // // // combine all factors -// GaussianFactor::shared_ptr actual = removeAndCombineFactors(fg,kx(2)); +// GaussianFactor::shared_ptr actual = removeAndCombineFactors(fg,X(2)); // // // the expected linear factor // Matrix Al1 = Matrix_(4,2, @@ -183,9 +184,9 @@ TEST( GaussianFactorGraph, equals ) { // b(3) = 1.5; // // vector > meas; -// meas.push_back(make_pair(kl(1), Al1)); -// meas.push_back(make_pair(kx(1), Ax1)); -// meas.push_back(make_pair(kx(2), Ax2)); +// meas.push_back(make_pair(L(1), Al1)); +// meas.push_back(make_pair(X(1), Ax1)); +// meas.push_back(make_pair(X(2), Ax2)); // GaussianFactor expected(meas, b, ones(4)); // // // check if the two factors are the same @@ -195,7 +196,7 @@ TEST( GaussianFactorGraph, equals ) { /* ************************************************************************* */ TEST( GaussianFactorGraph, eliminateOne_x1 ) { - Ordering ordering; ordering += kx(1),kl(1),kx(2); + Ordering ordering; ordering += X(1),L(1),X(2); GaussianFactorGraph fg = createGaussianFactorGraph(ordering); GaussianFactorGraph::FactorizationResult result = inference::eliminateOne(fg, 0, EliminateQR); @@ -203,7 +204,7 @@ TEST( GaussianFactorGraph, eliminateOne_x1 ) // create expected Conditional Gaussian Matrix I = 15*eye(2), R11 = I, S12 = -0.111111*I, S13 = -0.444444*I; Vector d = Vector_(2, -0.133333, -0.0222222), sigma = ones(2); - GaussianConditional expected(ordering[kx(1)],15*d,R11,ordering[kl(1)],S12,ordering[kx(2)],S13,sigma); + GaussianConditional expected(ordering[X(1)],15*d,R11,ordering[L(1)],S12,ordering[X(2)],S13,sigma); EXPECT(assert_equal(expected,*result.first,tol)); } @@ -211,7 +212,7 @@ TEST( GaussianFactorGraph, eliminateOne_x1 ) /* ************************************************************************* */ TEST( GaussianFactorGraph, eliminateOne_x2 ) { - Ordering ordering; ordering += kx(2),kl(1),kx(1); + Ordering ordering; ordering += X(2),L(1),X(1); GaussianFactorGraph fg = createGaussianFactorGraph(ordering); GaussianConditional::shared_ptr actual = inference::eliminateOne(fg, 0, EliminateQR).first; @@ -219,7 +220,7 @@ TEST( GaussianFactorGraph, eliminateOne_x2 ) double sig = 0.0894427; Matrix I = eye(2)/sig, R11 = I, S12 = -0.2*I, S13 = -0.8*I; Vector d = Vector_(2, 0.2, -0.14)/sig, sigma = ones(2); - GaussianConditional expected(ordering[kx(2)],d,R11,ordering[kl(1)],S12,ordering[kx(1)],S13,sigma); + GaussianConditional expected(ordering[X(2)],d,R11,ordering[L(1)],S12,ordering[X(1)],S13,sigma); EXPECT(assert_equal(expected,*actual,tol)); } @@ -227,7 +228,7 @@ TEST( GaussianFactorGraph, eliminateOne_x2 ) /* ************************************************************************* */ TEST( GaussianFactorGraph, eliminateOne_l1 ) { - Ordering ordering; ordering += kl(1),kx(1),kx(2); + Ordering ordering; ordering += L(1),X(1),X(2); GaussianFactorGraph fg = createGaussianFactorGraph(ordering); GaussianConditional::shared_ptr actual = inference::eliminateOne(fg, 0, EliminateQR).first; @@ -235,7 +236,7 @@ TEST( GaussianFactorGraph, eliminateOne_l1 ) double sig = sqrt(2.0)/10.; Matrix I = eye(2)/sig, R11 = I, S12 = -0.5*I, S13 = -0.5*I; Vector d = Vector_(2, -0.1, 0.25)/sig, sigma = ones(2); - GaussianConditional expected(ordering[kl(1)],d,R11,ordering[kx(1)],S12,ordering[kx(2)],S13,sigma); + GaussianConditional expected(ordering[L(1)],d,R11,ordering[X(1)],S12,ordering[X(2)],S13,sigma); EXPECT(assert_equal(expected,*actual,tol)); } @@ -243,16 +244,16 @@ TEST( GaussianFactorGraph, eliminateOne_l1 ) /* ************************************************************************* */ TEST( GaussianFactorGraph, eliminateOne_x1_fast ) { - Ordering ordering; ordering += kx(1),kl(1),kx(2); + Ordering ordering; ordering += X(1),L(1),X(2); GaussianFactorGraph fg = createGaussianFactorGraph(ordering); - GaussianFactorGraph::FactorizationResult result = inference::eliminateOne(fg, ordering[kx(1)], EliminateQR); + GaussianFactorGraph::FactorizationResult result = inference::eliminateOne(fg, ordering[X(1)], EliminateQR); GaussianConditional::shared_ptr conditional = result.first; GaussianFactorGraph remaining = result.second; // create expected Conditional Gaussian Matrix I = 15*eye(2), R11 = I, S12 = -0.111111*I, S13 = -0.444444*I; Vector d = Vector_(2, -0.133333, -0.0222222), sigma = ones(2); - GaussianConditional expected(ordering[kx(1)],15*d,R11,ordering[kl(1)],S12,ordering[kx(2)],S13,sigma); + GaussianConditional expected(ordering[X(1)],15*d,R11,ordering[L(1)],S12,ordering[X(2)],S13,sigma); // Create expected remaining new factor JacobianFactor expectedFactor(1, Matrix_(4,2, @@ -274,15 +275,15 @@ TEST( GaussianFactorGraph, eliminateOne_x1_fast ) /* ************************************************************************* */ TEST( GaussianFactorGraph, eliminateOne_x2_fast ) { - Ordering ordering; ordering += kx(1),kl(1),kx(2); + Ordering ordering; ordering += X(1),L(1),X(2); GaussianFactorGraph fg = createGaussianFactorGraph(ordering); - GaussianConditional::shared_ptr actual = inference::eliminateOne(fg, ordering[kx(2)], EliminateQR).first; + GaussianConditional::shared_ptr actual = inference::eliminateOne(fg, ordering[X(2)], EliminateQR).first; // create expected Conditional Gaussian double sig = 0.0894427; Matrix I = eye(2)/sig, R11 = I, S12 = -0.2*I, S13 = -0.8*I; Vector d = Vector_(2, 0.2, -0.14)/sig, sigma = ones(2); - GaussianConditional expected(ordering[kx(2)],d,R11,ordering[kx(1)],S13,ordering[kl(1)],S12,sigma); + GaussianConditional expected(ordering[X(2)],d,R11,ordering[X(1)],S13,ordering[L(1)],S12,sigma); EXPECT(assert_equal(expected,*actual,tol)); } @@ -290,15 +291,15 @@ TEST( GaussianFactorGraph, eliminateOne_x2_fast ) /* ************************************************************************* */ TEST( GaussianFactorGraph, eliminateOne_l1_fast ) { - Ordering ordering; ordering += kx(1),kl(1),kx(2); + Ordering ordering; ordering += X(1),L(1),X(2); GaussianFactorGraph fg = createGaussianFactorGraph(ordering); - GaussianConditional::shared_ptr actual = inference::eliminateOne(fg, ordering[kl(1)], EliminateQR).first; + GaussianConditional::shared_ptr actual = inference::eliminateOne(fg, ordering[L(1)], EliminateQR).first; // create expected Conditional Gaussian double sig = sqrt(2.0)/10.; Matrix I = eye(2)/sig, R11 = I, S12 = -0.5*I, S13 = -0.5*I; Vector d = Vector_(2, -0.1, 0.25)/sig, sigma = ones(2); - GaussianConditional expected(ordering[kl(1)],d,R11,ordering[kx(1)],S12,ordering[kx(2)],S13,sigma); + GaussianConditional expected(ordering[L(1)],d,R11,ordering[X(1)],S12,ordering[X(2)],S13,sigma); EXPECT(assert_equal(expected,*actual,tol)); } @@ -310,18 +311,18 @@ TEST( GaussianFactorGraph, eliminateAll ) Matrix I = eye(2); Ordering ordering; - ordering += kx(2),kl(1),kx(1); + ordering += X(2),L(1),X(1); Vector d1 = Vector_(2, -0.1,-0.1); - GaussianBayesNet expected = simpleGaussian(ordering[kx(1)],d1,0.1); + GaussianBayesNet expected = simpleGaussian(ordering[X(1)],d1,0.1); double sig1 = 0.149071; Vector d2 = Vector_(2, 0.0, 0.2)/sig1, sigma2 = ones(2); - push_front(expected,ordering[kl(1)],d2, I/sig1,ordering[kx(1)], (-1)*I/sig1,sigma2); + push_front(expected,ordering[L(1)],d2, I/sig1,ordering[X(1)], (-1)*I/sig1,sigma2); double sig2 = 0.0894427; Vector d3 = Vector_(2, 0.2, -0.14)/sig2, sigma3 = ones(2); - push_front(expected,ordering[kx(2)],d3, I/sig2,ordering[kl(1)], (-0.2)*I/sig2, ordering[kx(1)], (-0.8)*I/sig2, sigma3); + push_front(expected,ordering[X(2)],d3, I/sig2,ordering[L(1)], (-0.2)*I/sig2, ordering[X(1)], (-0.8)*I/sig2, sigma3); // Check one ordering GaussianFactorGraph fg1 = createGaussianFactorGraph(ordering); @@ -339,20 +340,20 @@ TEST( GaussianFactorGraph, eliminateAll ) // Matrix I = eye(2); // // Vector d1 = Vector_(2, -0.1,-0.1); -// GaussianBayesNet expected = simpleGaussian(kx(1),d1,0.1); +// GaussianBayesNet expected = simpleGaussian(X(1),d1,0.1); // // double sig1 = 0.149071; // Vector d2 = Vector_(2, 0.0, 0.2)/sig1, sigma2 = ones(2); -// push_front(expected,kl(1),d2, I/sig1,kx(1), (-1)*I/sig1,sigma2); +// push_front(expected,L(1),d2, I/sig1,X(1), (-1)*I/sig1,sigma2); // // double sig2 = 0.0894427; // Vector d3 = Vector_(2, 0.2, -0.14)/sig2, sigma3 = ones(2); -// push_front(expected,kx(2),d3, I/sig2,kl(1), (-0.2)*I/sig2, kx(1), (-0.8)*I/sig2, sigma3); +// push_front(expected,X(2),d3, I/sig2,L(1), (-0.2)*I/sig2, X(1), (-0.8)*I/sig2, sigma3); // // // Check one ordering // GaussianFactorGraph fg1 = createGaussianFactorGraph(); // Ordering ordering; -// ordering += kx(2),kl(1),kx(1); +// ordering += X(2),L(1),X(1); // GaussianBayesNet actual = fg1.eliminate(ordering, false); // EXPECT(assert_equal(expected,actual,tol)); //} @@ -360,16 +361,16 @@ TEST( GaussianFactorGraph, eliminateAll ) ///* ************************************************************************* */ //TEST( GaussianFactorGraph, add_priors ) //{ -// Ordering ordering; ordering += kl(1),kx(1),kx(2); +// Ordering ordering; ordering += L(1),X(1),X(2); // GaussianFactorGraph fg = createGaussianFactorGraph(ordering); // GaussianFactorGraph actual = fg.add_priors(3, vector(3,2)); // GaussianFactorGraph expected = createGaussianFactorGraph(ordering); // Matrix A = eye(2); // Vector b = zero(2); // SharedDiagonal sigma = sharedSigma(2,3.0); -// expected.push_back(GaussianFactor::shared_ptr(new JacobianFactor(ordering[kl(1)],A,b,sigma))); -// expected.push_back(GaussianFactor::shared_ptr(new JacobianFactor(ordering[kx(1)],A,b,sigma))); -// expected.push_back(GaussianFactor::shared_ptr(new JacobianFactor(ordering[kx(2)],A,b,sigma))); +// expected.push_back(GaussianFactor::shared_ptr(new JacobianFactor(ordering[L(1)],A,b,sigma))); +// expected.push_back(GaussianFactor::shared_ptr(new JacobianFactor(ordering[X(1)],A,b,sigma))); +// expected.push_back(GaussianFactor::shared_ptr(new JacobianFactor(ordering[X(2)],A,b,sigma))); // EXPECT(assert_equal(expected,actual)); //} @@ -377,7 +378,7 @@ TEST( GaussianFactorGraph, eliminateAll ) TEST( GaussianFactorGraph, copying ) { // Create a graph - Ordering ordering; ordering += kx(2),kl(1),kx(1); + Ordering ordering; ordering += X(2),L(1),X(1); GaussianFactorGraph actual = createGaussianFactorGraph(ordering); // Copy the graph ! @@ -398,7 +399,7 @@ TEST( GaussianFactorGraph, copying ) //{ // // render with a given ordering // Ordering ord; -// ord += kx(2),kl(1),kx(1); +// ord += X(2),L(1),X(1); // // // Create a graph // GaussianFactorGraph fg = createGaussianFactorGraph(ordering); @@ -437,7 +438,7 @@ TEST( GaussianFactorGraph, copying ) TEST( GaussianFactorGraph, CONSTRUCTOR_GaussianBayesNet ) { Ordering ord; - ord += kx(2),kl(1),kx(1); + ord += X(2),L(1),X(1); GaussianFactorGraph fg = createGaussianFactorGraph(ord); // render with a given ordering @@ -457,20 +458,20 @@ TEST( GaussianFactorGraph, CONSTRUCTOR_GaussianBayesNet ) /* ************************************************************************* */ TEST( GaussianFactorGraph, getOrdering) { - Ordering original; original += kl(1),kx(1),kx(2); + Ordering original; original += L(1),X(1),X(2); FactorGraph symbolic(createGaussianFactorGraph(original)); Permutation perm(*inference::PermutationCOLAMD(VariableIndex(symbolic))); Ordering actual = original; actual.permuteWithInverse((*perm.inverse())); - Ordering expected; expected += kl(1),kx(2),kx(1); + Ordering expected; expected += L(1),X(2),X(1); EXPECT(assert_equal(expected,actual)); } // SL-FIX TEST( GaussianFactorGraph, getOrdering2) //{ // Ordering expected; -// expected += kl(1),kx(1); +// expected += L(1),X(1); // GaussianFactorGraph fg = createGaussianFactorGraph(); -// set interested; interested += kl(1),kx(1); +// set interested; interested += L(1),X(1); // Ordering actual = fg.getOrdering(interested); // EXPECT(assert_equal(expected,actual)); //} @@ -479,7 +480,7 @@ TEST( GaussianFactorGraph, getOrdering) TEST( GaussianFactorGraph, optimize_Cholesky ) { // create an ordering - Ordering ord; ord += kx(2),kl(1),kx(1); + Ordering ord; ord += X(2),L(1),X(1); // create a graph GaussianFactorGraph fg = createGaussianFactorGraph(ord); @@ -497,7 +498,7 @@ TEST( GaussianFactorGraph, optimize_Cholesky ) TEST( GaussianFactorGraph, optimize_QR ) { // create an ordering - Ordering ord; ord += kx(2),kl(1),kx(1); + Ordering ord; ord += X(2),L(1),X(1); // create a graph GaussianFactorGraph fg = createGaussianFactorGraph(ord); @@ -515,7 +516,7 @@ TEST( GaussianFactorGraph, optimize_QR ) // SL-FIX TEST( GaussianFactorGraph, optimizeMultiFrontlas ) //{ // // create an ordering -// Ordering ord; ord += kx(2),kl(1),kx(1); +// Ordering ord; ord += X(2),L(1),X(1); // // // create a graph // GaussianFactorGraph fg = createGaussianFactorGraph(ord); @@ -533,7 +534,7 @@ TEST( GaussianFactorGraph, optimize_QR ) TEST( GaussianFactorGraph, combine) { // create an ordering - Ordering ord; ord += kx(2),kl(1),kx(1); + Ordering ord; ord += X(2),L(1),X(1); // create a test graph GaussianFactorGraph fg1 = createGaussianFactorGraph(ord); @@ -555,7 +556,7 @@ TEST( GaussianFactorGraph, combine) TEST( GaussianFactorGraph, combine2) { // create an ordering - Ordering ord; ord += kx(2),kl(1),kx(1); + Ordering ord; ord += X(2),L(1),X(1); // create a test graph GaussianFactorGraph fg1 = createGaussianFactorGraph(ord); @@ -588,13 +589,13 @@ void print(vector v) { // GaussianFactorGraph fg = createGaussianFactorGraph(); // // // ask for all factor indices connected to x1 -// list x1_factors = fg.factors(kx(1)); +// list x1_factors = fg.factors(X(1)); // size_t x1_indices[] = { 0, 1, 2 }; // list x1_expected(x1_indices, x1_indices + 3); // EXPECT(x1_factors==x1_expected); // // // ask for all factor indices connected to x2 -// list x2_factors = fg.factors(kx(2)); +// list x2_factors = fg.factors(X(2)); // size_t x2_indices[] = { 1, 3 }; // list x2_expected(x2_indices, x2_indices + 2); // EXPECT(x2_factors==x2_expected); @@ -612,7 +613,7 @@ void print(vector v) { // GaussianFactor::shared_ptr f2 = fg[2]; // // // call the function -// vector factors = fg.findAndRemoveFactors(kx(1)); +// vector factors = fg.findAndRemoveFactors(X(1)); // // // Check the factors // EXPECT(f0==factors[0]); @@ -637,7 +638,7 @@ TEST(GaussianFactorGraph, createSmoother) //{ // GaussianFactorGraph fg = createGaussianFactorGraph(); // Dimensions expected; -// insert(expected)(kl(1), 2)(kx(1), 2)(kx(2), 2); +// insert(expected)(L(1), 2)(X(1), 2)(X(2), 2); // Dimensions actual = fg.dimensions(); // EXPECT(expected==actual); //} @@ -647,7 +648,7 @@ TEST(GaussianFactorGraph, createSmoother) //{ // GaussianFactorGraph fg = createGaussianFactorGraph(); // Ordering expected; -// expected += kl(1),kx(1),kx(2); +// expected += L(1),X(1),X(2); // EXPECT(assert_equal(expected,fg.keys())); //} @@ -655,16 +656,16 @@ TEST(GaussianFactorGraph, createSmoother) // SL-NEEDED? TEST( GaussianFactorGraph, involves ) //{ // GaussianFactorGraph fg = createGaussianFactorGraph(); -// EXPECT(fg.involves(kl(1))); -// EXPECT(fg.involves(kx(1))); -// EXPECT(fg.involves(kx(2))); -// EXPECT(!fg.involves(kx(3))); +// EXPECT(fg.involves(L(1))); +// EXPECT(fg.involves(X(1))); +// EXPECT(fg.involves(X(2))); +// EXPECT(!fg.involves(X(3))); //} /* ************************************************************************* */ double error(const VectorValues& x) { // create an ordering - Ordering ord; ord += kx(2),kl(1),kx(1); + Ordering ord; ord += X(2),L(1),X(1); GaussianFactorGraph fg = createGaussianFactorGraph(ord); return fg.error(x); @@ -678,11 +679,11 @@ double error(const VectorValues& x) { // // Construct expected gradient // VectorValues expected; // -// // 2*f(x) = 100*(x1+c[kx(1)])^2 + 100*(x2-x1-[0.2;-0.1])^2 + 25*(l1-x1-[0.0;0.2])^2 + 25*(l1-x2-[-0.2;0.3])^2 +// // 2*f(x) = 100*(x1+c[X(1)])^2 + 100*(x2-x1-[0.2;-0.1])^2 + 25*(l1-x1-[0.0;0.2])^2 + 25*(l1-x2-[-0.2;0.3])^2 // // worked out: df/dx1 = 100*[0.1;0.1] + 100*[0.2;-0.1]) + 25*[0.0;0.2] = [10+20;10-10+5] = [30;5] -// expected.insert(kl(1),Vector_(2, 5.0,-12.5)); -// expected.insert(kx(1),Vector_(2, 30.0, 5.0)); -// expected.insert(kx(2),Vector_(2,-25.0, 17.5)); +// expected.insert(L(1),Vector_(2, 5.0,-12.5)); +// expected.insert(X(1),Vector_(2, 30.0, 5.0)); +// expected.insert(X(2),Vector_(2,-25.0, 17.5)); // // // Check the gradient at delta=0 // VectorValues zero = createZeroDelta(); @@ -695,7 +696,7 @@ double error(const VectorValues& x) { // // // Check the gradient at the solution (should be zero) // Ordering ord; -// ord += kx(2),kl(1),kx(1); +// ord += X(2),L(1),X(1); // GaussianFactorGraph fg2 = createGaussianFactorGraph(); // VectorValues solution = fg2.optimize(ord); // destructive // VectorValues actual2 = fg.gradient(solution); @@ -706,7 +707,7 @@ double error(const VectorValues& x) { TEST( GaussianFactorGraph, multiplication ) { // create an ordering - Ordering ord; ord += kx(2),kl(1),kx(1); + Ordering ord; ord += X(2),L(1),X(1); FactorGraph A = createGaussianFactorGraph(ord); VectorValues x = createCorrectDelta(ord); @@ -723,7 +724,7 @@ TEST( GaussianFactorGraph, multiplication ) // SL-NEEDED? TEST( GaussianFactorGraph, transposeMultiplication ) //{ // // create an ordering -// Ordering ord; ord += kx(2),kl(1),kx(1); +// Ordering ord; ord += X(2),L(1),X(1); // // GaussianFactorGraph A = createGaussianFactorGraph(ord); // Errors e; @@ -733,9 +734,9 @@ TEST( GaussianFactorGraph, multiplication ) // e += Vector_(2,-7.5,-5.0); // // VectorValues expected = createZeroDelta(ord), actual = A ^ e; -// expected[ord[kl(1)]] = Vector_(2, -37.5,-50.0); -// expected[ord[kx(1)]] = Vector_(2,-150.0, 25.0); -// expected[ord[kx(2)]] = Vector_(2, 187.5, 25.0); +// expected[ord[L(1)]] = Vector_(2, -37.5,-50.0); +// expected[ord[X(1)]] = Vector_(2,-150.0, 25.0); +// expected[ord[X(2)]] = Vector_(2, 187.5, 25.0); // EXPECT(assert_equal(expected,actual)); //} @@ -743,7 +744,7 @@ TEST( GaussianFactorGraph, multiplication ) // SL-NEEDED? TEST( GaussianFactorGraph, rhs ) //{ // // create an ordering -// Ordering ord; ord += kx(2),kl(1),kx(1); +// Ordering ord; ord += X(2),L(1),X(1); // // GaussianFactorGraph Ab = createGaussianFactorGraph(ord); // Errors expected = createZeroDelta(ord), actual = Ab.rhs(); @@ -759,21 +760,21 @@ TEST( GaussianFactorGraph, multiplication ) TEST( GaussianFactorGraph, elimination ) { Ordering ord; - ord += kx(1), kx(2); + ord += X(1), X(2); // Create Gaussian Factor Graph GaussianFactorGraph fg; Matrix Ap = eye(1), An = eye(1) * -1; Vector b = Vector_(1, 0.0); SharedDiagonal sigma = sharedSigma(1,2.0); - fg.add(ord[kx(1)], An, ord[kx(2)], Ap, b, sigma); - fg.add(ord[kx(1)], Ap, b, sigma); - fg.add(ord[kx(2)], Ap, b, sigma); + fg.add(ord[X(1)], An, ord[X(2)], Ap, b, sigma); + fg.add(ord[X(1)], Ap, b, sigma); + fg.add(ord[X(2)], Ap, b, sigma); // Eliminate GaussianBayesNet bayesNet = *GaussianSequentialSolver(fg).eliminate(); // Check sigma - EXPECT_DOUBLES_EQUAL(1.0,bayesNet[ord[kx(2)]]->get_sigmas()(0),1e-5); + EXPECT_DOUBLES_EQUAL(1.0,bayesNet[ord[X(2)]]->get_sigmas()(0),1e-5); // Check matrix Matrix R;Vector d; @@ -876,18 +877,18 @@ SharedDiagonal model = sharedSigma(2,1); // GaussianFactorGraph g; // Matrix I = eye(2); // Vector b = Vector_(0, 0, 0); -// g.add(kx(1), I, kx(2), I, b, model); -// g.add(kx(1), I, kx(3), I, b, model); -// g.add(kx(1), I, kx(4), I, b, model); -// g.add(kx(2), I, kx(3), I, b, model); -// g.add(kx(2), I, kx(4), I, b, model); -// g.add(kx(3), I, kx(4), I, b, model); +// g.add(X(1), I, X(2), I, b, model); +// g.add(X(1), I, X(3), I, b, model); +// g.add(X(1), I, X(4), I, b, model); +// g.add(X(2), I, X(3), I, b, model); +// g.add(X(2), I, X(4), I, b, model); +// g.add(X(3), I, X(4), I, b, model); // // map tree = g.findMinimumSpanningTree(); -// EXPECT(tree[kx(1)].compare(kx(1))==0); -// EXPECT(tree[kx(2)].compare(kx(1))==0); -// EXPECT(tree[kx(3)].compare(kx(1))==0); -// EXPECT(tree[kx(4)].compare(kx(1))==0); +// EXPECT(tree[X(1)].compare(X(1))==0); +// EXPECT(tree[X(2)].compare(X(1))==0); +// EXPECT(tree[X(3)].compare(X(1))==0); +// EXPECT(tree[X(4)].compare(X(1))==0); //} ///* ************************************************************************* */ @@ -896,17 +897,17 @@ SharedDiagonal model = sharedSigma(2,1); // GaussianFactorGraph g; // Matrix I = eye(2); // Vector b = Vector_(0, 0, 0); -// g.add(kx(1), I, kx(2), I, b, model); -// g.add(kx(1), I, kx(3), I, b, model); -// g.add(kx(1), I, kx(4), I, b, model); -// g.add(kx(2), I, kx(3), I, b, model); -// g.add(kx(2), I, kx(4), I, b, model); +// g.add(X(1), I, X(2), I, b, model); +// g.add(X(1), I, X(3), I, b, model); +// g.add(X(1), I, X(4), I, b, model); +// g.add(X(2), I, X(3), I, b, model); +// g.add(X(2), I, X(4), I, b, model); // // PredecessorMap tree; -// tree[kx(1)] = kx(1); -// tree[kx(2)] = kx(1); -// tree[kx(3)] = kx(1); -// tree[kx(4)] = kx(1); +// tree[X(1)] = X(1); +// tree[X(2)] = X(1); +// tree[X(3)] = X(1); +// tree[X(4)] = X(1); // // GaussianFactorGraph Ab1, Ab2; // g.split(tree, Ab1, Ab2); @@ -917,17 +918,17 @@ SharedDiagonal model = sharedSigma(2,1); /* ************************************************************************* */ TEST(GaussianFactorGraph, replace) { - Ordering ord; ord += kx(1),kx(2),kx(3),kx(4),kx(5),kx(6); + Ordering ord; ord += X(1),X(2),X(3),X(4),X(5),X(6); SharedDiagonal noise(sharedSigma(3, 1.0)); GaussianFactorGraph::sharedFactor f1(new JacobianFactor( - ord[kx(1)], eye(3,3), ord[kx(2)], eye(3,3), zero(3), noise)); + ord[X(1)], eye(3,3), ord[X(2)], eye(3,3), zero(3), noise)); GaussianFactorGraph::sharedFactor f2(new JacobianFactor( - ord[kx(2)], eye(3,3), ord[kx(3)], eye(3,3), zero(3), noise)); + ord[X(2)], eye(3,3), ord[X(3)], eye(3,3), zero(3), noise)); GaussianFactorGraph::sharedFactor f3(new JacobianFactor( - ord[kx(3)], eye(3,3), ord[kx(4)], eye(3,3), zero(3), noise)); + ord[X(3)], eye(3,3), ord[X(4)], eye(3,3), zero(3), noise)); GaussianFactorGraph::sharedFactor f4(new JacobianFactor( - ord[kx(5)], eye(3,3), ord[kx(6)], eye(3,3), zero(3), noise)); + ord[X(5)], eye(3,3), ord[X(6)], eye(3,3), zero(3), noise)); GaussianFactorGraph actual; actual.push_back(f1); @@ -963,7 +964,7 @@ TEST(GaussianFactorGraph, replace) // // // combine in a factor // Matrix Ab; SharedDiagonal noise; -// Ordering order; order += kx(2), kl(1), kx(1); +// Ordering order; order += X(2), L(1), X(1); // boost::tie(Ab, noise) = combineFactorsAndCreateMatrix(lfg, order, dimensions); // // // the expected augmented matrix @@ -991,26 +992,26 @@ TEST(GaussianFactorGraph, replace) // typedef GaussianFactorGraph::sharedFactor Factor; // SharedDiagonal model(Vector_(1, 0.5)); // GaussianFactorGraph fg; -// Factor factor1(new JacobianFactor(kx(1), Matrix_(1,1,1.), kx(2), Matrix_(1,1,1.), Vector_(1,1.), model)); -// Factor factor2(new JacobianFactor(kx(2), Matrix_(1,1,1.), kx(3), Matrix_(1,1,1.), Vector_(1,1.), model)); -// Factor factor3(new JacobianFactor(kx(3), Matrix_(1,1,1.), kx(3), Matrix_(1,1,1.), Vector_(1,1.), model)); +// Factor factor1(new JacobianFactor(X(1), Matrix_(1,1,1.), X(2), Matrix_(1,1,1.), Vector_(1,1.), model)); +// Factor factor2(new JacobianFactor(X(2), Matrix_(1,1,1.), X(3), Matrix_(1,1,1.), Vector_(1,1.), model)); +// Factor factor3(new JacobianFactor(X(3), Matrix_(1,1,1.), X(3), Matrix_(1,1,1.), Vector_(1,1.), model)); // fg.push_back(factor1); // fg.push_back(factor2); // fg.push_back(factor3); // -// Ordering frontals; frontals += kx(2), kx(1); +// Ordering frontals; frontals += X(2), X(1); // GaussianBayesNet bn = fg.eliminateFrontals(frontals); // // GaussianBayesNet bn_expected; -// GaussianBayesNet::sharedConditional conditional1(new GaussianConditional(kx(2), Vector_(1, 2.), Matrix_(1, 1, 2.), -// kx(1), Matrix_(1, 1, 1.), kx(3), Matrix_(1, 1, 1.), Vector_(1, 1.))); -// GaussianBayesNet::sharedConditional conditional2(new GaussianConditional(kx(1), Vector_(1, 0.), Matrix_(1, 1, -1.), -// kx(3), Matrix_(1, 1, 1.), Vector_(1, 1.))); +// GaussianBayesNet::sharedConditional conditional1(new GaussianConditional(X(2), Vector_(1, 2.), Matrix_(1, 1, 2.), +// X(1), Matrix_(1, 1, 1.), X(3), Matrix_(1, 1, 1.), Vector_(1, 1.))); +// GaussianBayesNet::sharedConditional conditional2(new GaussianConditional(X(1), Vector_(1, 0.), Matrix_(1, 1, -1.), +// X(3), Matrix_(1, 1, 1.), Vector_(1, 1.))); // bn_expected.push_back(conditional1); // bn_expected.push_back(conditional2); // EXPECT(assert_equal(bn_expected, bn)); // -// GaussianFactorGraph::sharedFactor factor_expected(new JacobianFactor(kx(3), Matrix_(1, 1, 2.), Vector_(1, 2.), SharedDiagonal(Vector_(1, 1.)))); +// GaussianFactorGraph::sharedFactor factor_expected(new JacobianFactor(X(3), Matrix_(1, 1, 2.), Vector_(1, 2.), SharedDiagonal(Vector_(1, 1.)))); // GaussianFactorGraph fg_expected; // fg_expected.push_back(factor_expected); // EXPECT(assert_equal(fg_expected, fg)); @@ -1026,8 +1027,8 @@ TEST(GaussianFactorGraph, createSmoother2) LONGS_EQUAL(5,fg2.size()); // eliminate - vector x3var; x3var.push_back(ordering[kx(3)]); - vector x1var; x1var.push_back(ordering[kx(1)]); + vector x3var; x3var.push_back(ordering[X(3)]); + vector x1var; x1var.push_back(ordering[X(1)]); GaussianBayesNet p_x3 = *GaussianSequentialSolver( *GaussianSequentialSolver(fg2).jointFactorGraph(x3var)).eliminate(); GaussianBayesNet p_x1 = *GaussianSequentialSolver( @@ -1044,7 +1045,7 @@ TEST(GaussianFactorGraph, hasConstraints) FactorGraph fgc2 = createSimpleConstraintGraph() ; EXPECT(hasConstraints(fgc2)); - Ordering ordering; ordering += kx(1), kx(2), kl(1); + Ordering ordering; ordering += X(1), X(2), L(1); FactorGraph fg = createGaussianFactorGraph(ordering); EXPECT(!hasConstraints(fg)); } diff --git a/tests/testGaussianISAM.cpp b/tests/testGaussianISAM.cpp index 4c798aa8d..03a747196 100644 --- a/tests/testGaussianISAM.cpp +++ b/tests/testGaussianISAM.cpp @@ -15,27 +15,28 @@ * @author Michael Kaess */ -#include -#include // for operator += -using namespace boost::assign; - -#include - -#include +#include #include +#include #include -#include #include #include #include -#include +#include +#include + +#include + +#include +#include // for operator += +using namespace boost::assign; using namespace std; using namespace gtsam; using namespace example; -Key kx(size_t i) { return Symbol('x',i); } -Key kl(size_t i) { return Symbol('l',i); } +using symbol_shorthand::X; +using symbol_shorthand::L; /* ************************************************************************* */ // Some numbers that should be consistent among all smoother tests @@ -49,7 +50,7 @@ const double tol = 1e-4; TEST_UNSAFE( ISAM, iSAM_smoother ) { Ordering ordering; - for (int t = 1; t <= 7; t++) ordering += kx(t); + for (int t = 1; t <= 7; t++) ordering += X(t); // Create smoother with 7 nodes GaussianFactorGraph smoother = createSmoother(7, ordering).first; @@ -82,7 +83,7 @@ TEST_UNSAFE( ISAM, iSAM_smoother ) // GaussianFactorGraph smoother = createSmoother(7); // // // Create initial tree from first 4 timestamps in reverse order ! -// Ordering ord; ord += kx(4),kx(3),kx(2),kx(1); +// Ordering ord; ord += X(4),X(3),X(2),X(1); // GaussianFactorGraph factors1; // for (int i=0;i<7;i++) factors1.push_back(smoother[i]); // GaussianISAM actual(*inference::Eliminate(factors1)); @@ -129,7 +130,7 @@ TEST_UNSAFE( BayesTree, linear_smoother_shortcuts ) EXPECT(assert_equal(empty,actual1,tol)); // Check the conditional P(C2|Root) - GaussianISAM::sharedClique C2 = isamTree[ordering[kx(5)]]; + GaussianISAM::sharedClique C2 = isamTree[ordering[X(5)]]; GaussianBayesNet actual2 = GaussianISAM::shortcut(C2,R); EXPECT(assert_equal(empty,actual2,tol)); @@ -137,8 +138,8 @@ TEST_UNSAFE( BayesTree, linear_smoother_shortcuts ) double sigma3 = 0.61808; Matrix A56 = Matrix_(2,2,-0.382022,0.,0.,-0.382022); GaussianBayesNet expected3; - push_front(expected3,ordering[kx(5)], zero(2), eye(2)/sigma3, ordering[kx(6)], A56/sigma3, ones(2)); - GaussianISAM::sharedClique C3 = isamTree[ordering[kx(4)]]; + push_front(expected3,ordering[X(5)], zero(2), eye(2)/sigma3, ordering[X(6)], A56/sigma3, ones(2)); + GaussianISAM::sharedClique C3 = isamTree[ordering[X(4)]]; GaussianBayesNet actual3 = GaussianISAM::shortcut(C3,R); EXPECT(assert_equal(expected3,actual3,tol)); @@ -146,8 +147,8 @@ TEST_UNSAFE( BayesTree, linear_smoother_shortcuts ) double sigma4 = 0.661968; Matrix A46 = Matrix_(2,2,-0.146067,0.,0.,-0.146067); GaussianBayesNet expected4; - push_front(expected4, ordering[kx(4)], zero(2), eye(2)/sigma4, ordering[kx(6)], A46/sigma4, ones(2)); - GaussianISAM::sharedClique C4 = isamTree[ordering[kx(3)]]; + push_front(expected4, ordering[X(4)], zero(2), eye(2)/sigma4, ordering[X(6)], A46/sigma4, ones(2)); + GaussianISAM::sharedClique C4 = isamTree[ordering[X(3)]]; GaussianBayesNet actual4 = GaussianISAM::shortcut(C4,R); EXPECT(assert_equal(expected4,actual4,tol)); } @@ -175,7 +176,7 @@ TEST_UNSAFE( BayesTree, balanced_smoother_marginals ) { // Create smoother with 7 nodes Ordering ordering; - ordering += kx(1),kx(3),kx(5),kx(7),kx(2),kx(6),kx(4); + ordering += X(1),X(3),X(5),X(7),X(2),X(6),X(4); GaussianFactorGraph smoother = createSmoother(7, ordering).first; // Create the Bayes tree @@ -192,48 +193,48 @@ TEST_UNSAFE( BayesTree, balanced_smoother_marginals ) double tol=1e-5; // Check marginal on x1 - GaussianBayesNet expected1 = simpleGaussian(ordering[kx(1)], zero(2), sigmax1); - GaussianBayesNet actual1 = *bayesTree.marginalBayesNet(ordering[kx(1)]); + GaussianBayesNet expected1 = simpleGaussian(ordering[X(1)], zero(2), sigmax1); + GaussianBayesNet actual1 = *bayesTree.marginalBayesNet(ordering[X(1)]); Matrix expectedCovarianceX1 = eye(2,2) * (sigmax1 * sigmax1); Matrix actualCovarianceX1; - actualCovarianceX1 = bayesTree.marginalCovariance(ordering[kx(1)]); + actualCovarianceX1 = bayesTree.marginalCovariance(ordering[X(1)]); EXPECT(assert_equal(expectedCovarianceX1, actualCovarianceX1, tol)); EXPECT(assert_equal(expected1,actual1,tol)); // Check marginal on x2 double sigx2 = 0.68712938; // FIXME: this should be corrected analytically - GaussianBayesNet expected2 = simpleGaussian(ordering[kx(2)], zero(2), sigx2); - GaussianBayesNet actual2 = *bayesTree.marginalBayesNet(ordering[kx(2)]); + GaussianBayesNet expected2 = simpleGaussian(ordering[X(2)], zero(2), sigx2); + GaussianBayesNet actual2 = *bayesTree.marginalBayesNet(ordering[X(2)]); Matrix expectedCovarianceX2 = eye(2,2) * (sigx2 * sigx2); Matrix actualCovarianceX2; - actualCovarianceX2 = bayesTree.marginalCovariance(ordering[kx(2)]); + actualCovarianceX2 = bayesTree.marginalCovariance(ordering[X(2)]); EXPECT(assert_equal(expectedCovarianceX2, actualCovarianceX2, tol)); EXPECT(assert_equal(expected2,actual2,tol)); // Check marginal on x3 - GaussianBayesNet expected3 = simpleGaussian(ordering[kx(3)], zero(2), sigmax3); - GaussianBayesNet actual3 = *bayesTree.marginalBayesNet(ordering[kx(3)]); + GaussianBayesNet expected3 = simpleGaussian(ordering[X(3)], zero(2), sigmax3); + GaussianBayesNet actual3 = *bayesTree.marginalBayesNet(ordering[X(3)]); Matrix expectedCovarianceX3 = eye(2,2) * (sigmax3 * sigmax3); Matrix actualCovarianceX3; - actualCovarianceX3 = bayesTree.marginalCovariance(ordering[kx(3)]); + actualCovarianceX3 = bayesTree.marginalCovariance(ordering[X(3)]); EXPECT(assert_equal(expectedCovarianceX3, actualCovarianceX3, tol)); EXPECT(assert_equal(expected3,actual3,tol)); // Check marginal on x4 - GaussianBayesNet expected4 = simpleGaussian(ordering[kx(4)], zero(2), sigmax4); - GaussianBayesNet actual4 = *bayesTree.marginalBayesNet(ordering[kx(4)]); + GaussianBayesNet expected4 = simpleGaussian(ordering[X(4)], zero(2), sigmax4); + GaussianBayesNet actual4 = *bayesTree.marginalBayesNet(ordering[X(4)]); Matrix expectedCovarianceX4 = eye(2,2) * (sigmax4 * sigmax4); Matrix actualCovarianceX4; - actualCovarianceX4 = bayesTree.marginalCovariance(ordering[kx(4)]); + actualCovarianceX4 = bayesTree.marginalCovariance(ordering[X(4)]); EXPECT(assert_equal(expectedCovarianceX4, actualCovarianceX4, tol)); EXPECT(assert_equal(expected4,actual4,tol)); // Check marginal on x7 (should be equal to x1) - GaussianBayesNet expected7 = simpleGaussian(ordering[kx(7)], zero(2), sigmax7); - GaussianBayesNet actual7 = *bayesTree.marginalBayesNet(ordering[kx(7)]); + GaussianBayesNet expected7 = simpleGaussian(ordering[X(7)], zero(2), sigmax7); + GaussianBayesNet actual7 = *bayesTree.marginalBayesNet(ordering[X(7)]); Matrix expectedCovarianceX7 = eye(2,2) * (sigmax7 * sigmax7); Matrix actualCovarianceX7; - actualCovarianceX7 = bayesTree.marginalCovariance(ordering[kx(7)]); + actualCovarianceX7 = bayesTree.marginalCovariance(ordering[X(7)]); EXPECT(assert_equal(expectedCovarianceX7, actualCovarianceX7, tol)); EXPECT(assert_equal(expected7,actual7,tol)); } @@ -243,7 +244,7 @@ TEST_UNSAFE( BayesTree, balanced_smoother_shortcuts ) { // Create smoother with 7 nodes Ordering ordering; - ordering += kx(1),kx(3),kx(5),kx(7),kx(2),kx(6),kx(4); + ordering += X(1),X(3),X(5),X(7),X(2),X(6),X(4); GaussianFactorGraph smoother = createSmoother(7, ordering).first; // Create the Bayes tree @@ -257,19 +258,19 @@ TEST_UNSAFE( BayesTree, balanced_smoother_shortcuts ) EXPECT(assert_equal(empty,actual1,tol)); // Check the conditional P(C2|Root) - GaussianISAM::sharedClique C2 = isamTree[ordering[kx(3)]]; + GaussianISAM::sharedClique C2 = isamTree[ordering[X(3)]]; GaussianBayesNet actual2 = GaussianISAM::shortcut(C2,R); EXPECT(assert_equal(empty,actual2,tol)); // Check the conditional P(C3|Root), which should be equal to P(x2|x4) /** TODO: Note for multifrontal conditional: - * p_x2_x4 is now an element conditional of the multifrontal conditional bayesTree[ordering[kx(2)]]->conditional() + * p_x2_x4 is now an element conditional of the multifrontal conditional bayesTree[ordering[X(2)]]->conditional() * We don't know yet how to take it out. */ -// GaussianConditional::shared_ptr p_x2_x4 = bayesTree[ordering[kx(2)]]->conditional(); +// GaussianConditional::shared_ptr p_x2_x4 = bayesTree[ordering[X(2)]]->conditional(); // p_x2_x4->print("Conditional p_x2_x4: "); // GaussianBayesNet expected3(p_x2_x4); -// GaussianISAM::sharedClique C3 = isamTree[ordering[kx(1)]]; +// GaussianISAM::sharedClique C3 = isamTree[ordering[X(1)]]; // GaussianBayesNet actual3 = GaussianISAM::shortcut(C3,R); // EXPECT(assert_equal(expected3,actual3,tol)); } @@ -279,7 +280,7 @@ TEST_UNSAFE( BayesTree, balanced_smoother_shortcuts ) //{ // // Create smoother with 7 nodes // Ordering ordering; -// ordering += kx(1),kx(3),kx(5),kx(7),kx(2),kx(6),kx(4); +// ordering += X(1),X(3),X(5),X(7),X(2),X(6),X(4); // GaussianFactorGraph smoother = createSmoother(7, ordering).first; // // // Create the Bayes tree @@ -288,9 +289,9 @@ TEST_UNSAFE( BayesTree, balanced_smoother_shortcuts ) // // // Check the clique marginal P(C3) // double sigmax2_alt = 1/1.45533; // THIS NEEDS TO BE CHECKED! -// GaussianBayesNet expected = simpleGaussian(ordering[kx(2)],zero(2),sigmax2_alt); -// push_front(expected,ordering[kx(1)], zero(2), eye(2)*sqrt(2), ordering[kx(2)], -eye(2)*sqrt(2)/2, ones(2)); -// GaussianISAM::sharedClique R = bayesTree.root(), C3 = bayesTree[ordering[kx(1)]]; +// GaussianBayesNet expected = simpleGaussian(ordering[X(2)],zero(2),sigmax2_alt); +// push_front(expected,ordering[X(1)], zero(2), eye(2)*sqrt(2), ordering[X(2)], -eye(2)*sqrt(2)/2, ones(2)); +// GaussianISAM::sharedClique R = bayesTree.root(), C3 = bayesTree[ordering[X(1)]]; // GaussianFactorGraph marginal = C3->marginal(R); // GaussianVariableIndex varIndex(marginal); // Permutation toFront(Permutation::PullToFront(C3->keys(), varIndex.size())); @@ -308,7 +309,7 @@ TEST_UNSAFE( BayesTree, balanced_smoother_joint ) { // Create smoother with 7 nodes Ordering ordering; - ordering += kx(1),kx(3),kx(5),kx(7),kx(2),kx(6),kx(4); + ordering += X(1),X(3),X(5),X(7),X(2),X(6),X(4); GaussianFactorGraph smoother = createSmoother(7, ordering).first; // Create the Bayes tree, expected to look like: @@ -327,41 +328,41 @@ TEST_UNSAFE( BayesTree, balanced_smoother_joint ) GaussianBayesNet expected1; // Why does the sign get flipped on the prior? GaussianConditional::shared_ptr - parent1(new GaussianConditional(ordering[kx(7)], zero(2), -1*I/sigmax7, ones(2))); + parent1(new GaussianConditional(ordering[X(7)], zero(2), -1*I/sigmax7, ones(2))); expected1.push_front(parent1); - push_front(expected1,ordering[kx(1)], zero(2), I/sigmax7, ordering[kx(7)], A/sigmax7, sigma); - GaussianBayesNet actual1 = *bayesTree.jointBayesNet(ordering[kx(1)],ordering[kx(7)]); + push_front(expected1,ordering[X(1)], zero(2), I/sigmax7, ordering[X(7)], A/sigmax7, sigma); + GaussianBayesNet actual1 = *bayesTree.jointBayesNet(ordering[X(1)],ordering[X(7)]); EXPECT(assert_equal(expected1,actual1,tol)); // // Check the joint density P(x7,x1) factored as P(x7|x1)P(x1) // GaussianBayesNet expected2; // GaussianConditional::shared_ptr -// parent2(new GaussianConditional(ordering[kx(1)], zero(2), -1*I/sigmax1, ones(2))); +// parent2(new GaussianConditional(ordering[X(1)], zero(2), -1*I/sigmax1, ones(2))); // expected2.push_front(parent2); -// push_front(expected2,ordering[kx(7)], zero(2), I/sigmax1, ordering[kx(1)], A/sigmax1, sigma); -// GaussianBayesNet actual2 = *bayesTree.jointBayesNet(ordering[kx(7)],ordering[kx(1)]); +// push_front(expected2,ordering[X(7)], zero(2), I/sigmax1, ordering[X(1)], A/sigmax1, sigma); +// GaussianBayesNet actual2 = *bayesTree.jointBayesNet(ordering[X(7)],ordering[X(1)]); // EXPECT(assert_equal(expected2,actual2,tol)); // Check the joint density P(x1,x4), i.e. with a root variable GaussianBayesNet expected3; GaussianConditional::shared_ptr - parent3(new GaussianConditional(ordering[kx(4)], zero(2), I/sigmax4, ones(2))); + parent3(new GaussianConditional(ordering[X(4)], zero(2), I/sigmax4, ones(2))); expected3.push_front(parent3); double sig14 = 0.784465; Matrix A14 = -0.0769231*I; - push_front(expected3,ordering[kx(1)], zero(2), I/sig14, ordering[kx(4)], A14/sig14, sigma); - GaussianBayesNet actual3 = *bayesTree.jointBayesNet(ordering[kx(1)],ordering[kx(4)]); + push_front(expected3,ordering[X(1)], zero(2), I/sig14, ordering[X(4)], A14/sig14, sigma); + GaussianBayesNet actual3 = *bayesTree.jointBayesNet(ordering[X(1)],ordering[X(4)]); EXPECT(assert_equal(expected3,actual3,tol)); // // Check the joint density P(x4,x1), i.e. with a root variable, factored the other way // GaussianBayesNet expected4; // GaussianConditional::shared_ptr -// parent4(new GaussianConditional(ordering[kx(1)], zero(2), -1.0*I/sigmax1, ones(2))); +// parent4(new GaussianConditional(ordering[X(1)], zero(2), -1.0*I/sigmax1, ones(2))); // expected4.push_front(parent4); // double sig41 = 0.668096; // Matrix A41 = -0.055794*I; -// push_front(expected4,ordering[kx(4)], zero(2), I/sig41, ordering[kx(1)], A41/sig41, sigma); -// GaussianBayesNet actual4 = *bayesTree.jointBayesNet(ordering[kx(4)],ordering[kx(1)]); +// push_front(expected4,ordering[X(4)], zero(2), I/sig41, ordering[X(1)], A41/sig41, sigma); +// GaussianBayesNet actual4 = *bayesTree.jointBayesNet(ordering[X(4)],ordering[X(1)]); // EXPECT(assert_equal(expected4,actual4,tol)); } diff --git a/tests/testGaussianISAM2.cpp b/tests/testGaussianISAM2.cpp index 40e1ca4e1..cf2842af9 100644 --- a/tests/testGaussianISAM2.cpp +++ b/tests/testGaussianISAM2.cpp @@ -4,13 +4,6 @@ * @author Michael Kaess */ -#include -#include // for operator += -#include -using namespace boost::assign; - -#include - #include #include #include @@ -21,26 +14,32 @@ using namespace boost::assign; #include #include +#include + +#include +#include // for operator += +#include +using namespace boost::assign; + using namespace std; using namespace gtsam; -using namespace example; using boost::shared_ptr; const double tol = 1e-4; +// SETDEBUG("ISAM2 update", true); +// SETDEBUG("ISAM2 update verbose", true); +// SETDEBUG("ISAM2 recalculate", true); + +// Set up parameters +SharedDiagonal odoNoise = sharedSigmas(Vector_(3, 0.1, 0.1, M_PI/100.0)); +SharedDiagonal brNoise = sharedSigmas(Vector_(2, M_PI/100.0, 0.1)); + ISAM2 createSlamlikeISAM2( boost::optional init_values = boost::none, boost::optional full_graph = boost::none, const ISAM2Params& params = ISAM2Params(ISAM2GaussNewtonParams(0.001), 0.0, 0, false, true)) { - // Pose and landmark key types from planarSLAM - using planarSLAM::PoseKey; - using planarSLAM::PointKey; - - // Set up parameters - SharedDiagonal odoNoise = sharedSigmas(Vector_(3, 0.1, 0.1, M_PI/100.0)); - SharedDiagonal brNoise = sharedSigmas(Vector_(2, M_PI/100.0, 0.1)); - // These variables will be reused and accumulate factors and values ISAM2 isam(params); // ISAM2 isam(ISAM2Params(ISAM2GaussNewtonParams(0.001), 0.0, 0, false, true)); @@ -57,8 +56,8 @@ ISAM2 createSlamlikeISAM2( fullgraph.push_back(newfactors); Values init; - init.insert(PoseKey(0), Pose2(0.01, 0.01, 0.01)); - fullinit.insert(PoseKey(0), Pose2(0.01, 0.01, 0.01)); + init.insert((0), Pose2(0.01, 0.01, 0.01)); + fullinit.insert((0), Pose2(0.01, 0.01, 0.01)); isam.update(newfactors, init); } @@ -70,8 +69,8 @@ ISAM2 createSlamlikeISAM2( fullgraph.push_back(newfactors); Values init; - init.insert(PoseKey(i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); - fullinit.insert(PoseKey(i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); + init.insert((i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); + fullinit.insert((i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); isam.update(newfactors, init); } @@ -80,17 +79,17 @@ ISAM2 createSlamlikeISAM2( { planarSLAM::Graph newfactors; newfactors.addOdometry(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise); - newfactors.addBearingRange(i, 0, Rot2::fromAngle(M_PI/4.0), 5.0, brNoise); - newfactors.addBearingRange(i, 1, Rot2::fromAngle(-M_PI/4.0), 5.0, brNoise); + newfactors.addBearingRange(i, 100, Rot2::fromAngle(M_PI/4.0), 5.0, brNoise); + newfactors.addBearingRange(i, 101, Rot2::fromAngle(-M_PI/4.0), 5.0, brNoise); fullgraph.push_back(newfactors); Values init; - init.insert(PoseKey(i+1), Pose2(1.01, 0.01, 0.01)); - init.insert(PointKey(0), Point2(5.0/sqrt(2.0), 5.0/sqrt(2.0))); - init.insert(PointKey(1), Point2(5.0/sqrt(2.0), -5.0/sqrt(2.0))); - fullinit.insert(PoseKey(i+1), Pose2(1.01, 0.01, 0.01)); - fullinit.insert(PointKey(0), Point2(5.0/sqrt(2.0), 5.0/sqrt(2.0))); - fullinit.insert(PointKey(1), Point2(5.0/sqrt(2.0), -5.0/sqrt(2.0))); + init.insert((i+1), Pose2(1.01, 0.01, 0.01)); + init.insert(100, Point2(5.0/sqrt(2.0), 5.0/sqrt(2.0))); + init.insert(101, Point2(5.0/sqrt(2.0), -5.0/sqrt(2.0))); + fullinit.insert((i+1), Pose2(1.01, 0.01, 0.01)); + fullinit.insert(100, Point2(5.0/sqrt(2.0), 5.0/sqrt(2.0))); + fullinit.insert(101, Point2(5.0/sqrt(2.0), -5.0/sqrt(2.0))); isam.update(newfactors, init); ++ i; @@ -103,8 +102,8 @@ ISAM2 createSlamlikeISAM2( fullgraph.push_back(newfactors); Values init; - init.insert(PoseKey(i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); - fullinit.insert(PoseKey(i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); + init.insert((i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); + fullinit.insert((i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); isam.update(newfactors, init); } @@ -113,13 +112,13 @@ ISAM2 createSlamlikeISAM2( { planarSLAM::Graph newfactors; newfactors.addOdometry(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise); - newfactors.addBearingRange(i, 0, Rot2::fromAngle(M_PI/4.0 + M_PI/16.0), 4.5, brNoise); - newfactors.addBearingRange(i, 1, Rot2::fromAngle(-M_PI/4.0 + M_PI/16.0), 4.5, brNoise); + newfactors.addBearingRange(i, 100, Rot2::fromAngle(M_PI/4.0 + M_PI/16.0), 4.5, brNoise); + newfactors.addBearingRange(i, 101, Rot2::fromAngle(-M_PI/4.0 + M_PI/16.0), 4.5, brNoise); fullgraph.push_back(newfactors); Values init; - init.insert(PoseKey(i+1), Pose2(6.9, 0.1, 0.01)); - fullinit.insert(PoseKey(i+1), Pose2(6.9, 0.1, 0.01)); + init.insert((i+1), Pose2(6.9, 0.1, 0.01)); + fullinit.insert((i+1), Pose2(6.9, 0.1, 0.01)); isam.update(newfactors, init); ++ i; @@ -139,10 +138,10 @@ TEST_UNSAFE(ISAM2, AddVariables) { // Create initial state Values theta; - theta.insert(planarSLAM::PoseKey(0), Pose2(.1, .2, .3)); - theta.insert(planarSLAM::PointKey(0), Point2(.4, .5)); + theta.insert((0), Pose2(.1, .2, .3)); + theta.insert(100, Point2(.4, .5)); Values newTheta; - newTheta.insert(planarSLAM::PoseKey(1), Pose2(.6, .7, .8)); + newTheta.insert((1), Pose2(.6, .7, .8)); VectorValues deltaUnpermuted; deltaUnpermuted.insert(0, Vector_(3, .1, .2, .3)); @@ -176,21 +175,21 @@ TEST_UNSAFE(ISAM2, AddVariables) { vector replacedKeys(2, false); - Ordering ordering; ordering += planarSLAM::PointKey(0), planarSLAM::PoseKey(0); + Ordering ordering; ordering += 100, (0); ISAM2::Nodes nodes(2); // Verify initial state - LONGS_EQUAL(0, ordering[planarSLAM::PointKey(0)]); - LONGS_EQUAL(1, ordering[planarSLAM::PoseKey(0)]); - EXPECT(assert_equal(deltaUnpermuted[1], delta[ordering[planarSLAM::PointKey(0)]])); - EXPECT(assert_equal(deltaUnpermuted[0], delta[ordering[planarSLAM::PoseKey(0)]])); + LONGS_EQUAL(0, ordering[100]); + LONGS_EQUAL(1, ordering[(0)]); + EXPECT(assert_equal(deltaUnpermuted[1], delta[ordering[100]])); + EXPECT(assert_equal(deltaUnpermuted[0], delta[ordering[(0)]])); // Create expected state Values thetaExpected; - thetaExpected.insert(planarSLAM::PoseKey(0), Pose2(.1, .2, .3)); - thetaExpected.insert(planarSLAM::PointKey(0), Point2(.4, .5)); - thetaExpected.insert(planarSLAM::PoseKey(1), Pose2(.6, .7, .8)); + thetaExpected.insert((0), Pose2(.1, .2, .3)); + thetaExpected.insert(100, Point2(.4, .5)); + thetaExpected.insert((1), Pose2(.6, .7, .8)); VectorValues deltaUnpermutedExpected; deltaUnpermutedExpected.insert(0, Vector_(3, .1, .2, .3)); @@ -230,7 +229,7 @@ TEST_UNSAFE(ISAM2, AddVariables) { vector replacedKeysExpected(3, false); - Ordering orderingExpected; orderingExpected += planarSLAM::PointKey(0), planarSLAM::PoseKey(0), planarSLAM::PoseKey(1); + Ordering orderingExpected; orderingExpected += 100, (0), (1); ISAM2::Nodes nodesExpected( 3, ISAM2::sharedClique()); @@ -255,10 +254,10 @@ TEST_UNSAFE(ISAM2, AddVariables) { // using namespace gtsam::planarSLAM; // typedef GaussianISAM2::Impl Impl; // -// Ordering ordering; ordering += PointKey(0), PoseKey(0), PoseKey(1); +// Ordering ordering; ordering += (0), (0), (1); // planarSLAM::Graph graph; -// graph.addPrior(PoseKey(0), Pose2(), sharedUnit(Pose2::dimension)); -// graph.addRange(PoseKey(0), PointKey(0), 1.0, sharedUnit(1)); +// graph.addPrior((0), Pose2(), sharedUnit(Pose2::dimension)); +// graph.addRange((0), (0), 1.0, sharedUnit(1)); // // FastSet expected; // expected.insert(0); @@ -307,7 +306,7 @@ TEST(ISAM2, optimize2) { // Create initialization Values theta; - theta.insert(planarSLAM::PoseKey(0), Pose2(0.01, 0.01, 0.01)); + theta.insert((0), Pose2(0.01, 0.01, 0.01)); // Create conditional Vector d(3); d << -0.1, -0.1, -0.31831; @@ -318,7 +317,7 @@ TEST(ISAM2, optimize2) { GaussianConditional::shared_ptr conditional(new GaussianConditional(0, d, R, Vector::Ones(3))); // Create ordering - Ordering ordering; ordering += planarSLAM::PoseKey(0); + Ordering ordering; ordering += (0); // Expected vector VectorValues expected(1, 3); @@ -353,18 +352,6 @@ bool isam_check(const planarSLAM::Graph& fullgraph, const Values& fullinit, cons TEST(ISAM2, slamlike_solution_gaussnewton) { -// SETDEBUG("ISAM2 update", true); -// SETDEBUG("ISAM2 update verbose", true); -// SETDEBUG("ISAM2 recalculate", true); - - // Pose and landmark key types from planarSLAM - using planarSLAM::PoseKey; - using planarSLAM::PointKey; - - // Set up parameters - SharedDiagonal odoNoise = sharedSigmas(Vector_(3, 0.1, 0.1, M_PI/100.0)); - SharedDiagonal brNoise = sharedSigmas(Vector_(2, M_PI/100.0, 0.1)); - // These variables will be reused and accumulate factors and values ISAM2 isam(ISAM2Params(ISAM2GaussNewtonParams(0.001), 0.0, 0, false)); Values fullinit; @@ -380,8 +367,8 @@ TEST(ISAM2, slamlike_solution_gaussnewton) fullgraph.push_back(newfactors); Values init; - init.insert(PoseKey(0), Pose2(0.01, 0.01, 0.01)); - fullinit.insert(PoseKey(0), Pose2(0.01, 0.01, 0.01)); + init.insert((0), Pose2(0.01, 0.01, 0.01)); + fullinit.insert((0), Pose2(0.01, 0.01, 0.01)); isam.update(newfactors, init); } @@ -395,8 +382,8 @@ TEST(ISAM2, slamlike_solution_gaussnewton) fullgraph.push_back(newfactors); Values init; - init.insert(PoseKey(i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); - fullinit.insert(PoseKey(i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); + init.insert((i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); + fullinit.insert((i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); isam.update(newfactors, init); } @@ -405,17 +392,17 @@ TEST(ISAM2, slamlike_solution_gaussnewton) { planarSLAM::Graph newfactors; newfactors.addOdometry(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise); - newfactors.addBearingRange(i, 0, Rot2::fromAngle(M_PI/4.0), 5.0, brNoise); - newfactors.addBearingRange(i, 1, Rot2::fromAngle(-M_PI/4.0), 5.0, brNoise); + newfactors.addBearingRange(i, 100, Rot2::fromAngle(M_PI/4.0), 5.0, brNoise); + newfactors.addBearingRange(i, 101, Rot2::fromAngle(-M_PI/4.0), 5.0, brNoise); fullgraph.push_back(newfactors); Values init; - init.insert(PoseKey(i+1), Pose2(1.01, 0.01, 0.01)); - init.insert(PointKey(0), Point2(5.0/sqrt(2.0), 5.0/sqrt(2.0))); - init.insert(PointKey(1), Point2(5.0/sqrt(2.0), -5.0/sqrt(2.0))); - fullinit.insert(PoseKey(i+1), Pose2(1.01, 0.01, 0.01)); - fullinit.insert(PointKey(0), Point2(5.0/sqrt(2.0), 5.0/sqrt(2.0))); - fullinit.insert(PointKey(1), Point2(5.0/sqrt(2.0), -5.0/sqrt(2.0))); + init.insert((i+1), Pose2(1.01, 0.01, 0.01)); + init.insert(100, Point2(5.0/sqrt(2.0), 5.0/sqrt(2.0))); + init.insert(101, Point2(5.0/sqrt(2.0), -5.0/sqrt(2.0))); + fullinit.insert((i+1), Pose2(1.01, 0.01, 0.01)); + fullinit.insert(100, Point2(5.0/sqrt(2.0), 5.0/sqrt(2.0))); + fullinit.insert(101, Point2(5.0/sqrt(2.0), -5.0/sqrt(2.0))); isam.update(newfactors, init); ++ i; @@ -428,8 +415,8 @@ TEST(ISAM2, slamlike_solution_gaussnewton) fullgraph.push_back(newfactors); Values init; - init.insert(PoseKey(i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); - fullinit.insert(PoseKey(i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); + init.insert((i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); + fullinit.insert((i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); isam.update(newfactors, init); } @@ -438,13 +425,13 @@ TEST(ISAM2, slamlike_solution_gaussnewton) { planarSLAM::Graph newfactors; newfactors.addOdometry(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise); - newfactors.addBearingRange(i, 0, Rot2::fromAngle(M_PI/4.0 + M_PI/16.0), 4.5, brNoise); - newfactors.addBearingRange(i, 1, Rot2::fromAngle(-M_PI/4.0 + M_PI/16.0), 4.5, brNoise); + newfactors.addBearingRange(i, 100, Rot2::fromAngle(M_PI/4.0 + M_PI/16.0), 4.5, brNoise); + newfactors.addBearingRange(i, 101, Rot2::fromAngle(-M_PI/4.0 + M_PI/16.0), 4.5, brNoise); fullgraph.push_back(newfactors); Values init; - init.insert(PoseKey(i+1), Pose2(6.9, 0.1, 0.01)); - fullinit.insert(PoseKey(i+1), Pose2(6.9, 0.1, 0.01)); + init.insert((i+1), Pose2(6.9, 0.1, 0.01)); + fullinit.insert((i+1), Pose2(6.9, 0.1, 0.01)); isam.update(newfactors, init); ++ i; @@ -485,19 +472,6 @@ TEST(ISAM2, slamlike_solution_gaussnewton) /* ************************************************************************* */ TEST(ISAM2, slamlike_solution_dogleg) { - -// SETDEBUG("ISAM2 update", true); -// SETDEBUG("ISAM2 update verbose", true); -// SETDEBUG("ISAM2 recalculate", true); - - // Pose and landmark key types from planarSLAM - using planarSLAM::PoseKey; - using planarSLAM::PointKey; - - // Set up parameters - SharedDiagonal odoNoise = sharedSigmas(Vector_(3, 0.1, 0.1, M_PI/100.0)); - SharedDiagonal brNoise = sharedSigmas(Vector_(2, M_PI/100.0, 0.1)); - // These variables will be reused and accumulate factors and values ISAM2 isam(ISAM2Params(ISAM2DoglegParams(1.0), 0.0, 0, false)); Values fullinit; @@ -513,8 +487,8 @@ TEST(ISAM2, slamlike_solution_dogleg) fullgraph.push_back(newfactors); Values init; - init.insert(PoseKey(0), Pose2(0.01, 0.01, 0.01)); - fullinit.insert(PoseKey(0), Pose2(0.01, 0.01, 0.01)); + init.insert((0), Pose2(0.01, 0.01, 0.01)); + fullinit.insert((0), Pose2(0.01, 0.01, 0.01)); isam.update(newfactors, init); } @@ -528,8 +502,8 @@ TEST(ISAM2, slamlike_solution_dogleg) fullgraph.push_back(newfactors); Values init; - init.insert(PoseKey(i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); - fullinit.insert(PoseKey(i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); + init.insert((i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); + fullinit.insert((i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); isam.update(newfactors, init); } @@ -538,17 +512,17 @@ TEST(ISAM2, slamlike_solution_dogleg) { planarSLAM::Graph newfactors; newfactors.addOdometry(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise); - newfactors.addBearingRange(i, 0, Rot2::fromAngle(M_PI/4.0), 5.0, brNoise); - newfactors.addBearingRange(i, 1, Rot2::fromAngle(-M_PI/4.0), 5.0, brNoise); + newfactors.addBearingRange(i, 100, Rot2::fromAngle(M_PI/4.0), 5.0, brNoise); + newfactors.addBearingRange(i, 101, Rot2::fromAngle(-M_PI/4.0), 5.0, brNoise); fullgraph.push_back(newfactors); Values init; - init.insert(PoseKey(i+1), Pose2(1.01, 0.01, 0.01)); - init.insert(PointKey(0), Point2(5.0/sqrt(2.0), 5.0/sqrt(2.0))); - init.insert(PointKey(1), Point2(5.0/sqrt(2.0), -5.0/sqrt(2.0))); - fullinit.insert(PoseKey(i+1), Pose2(1.01, 0.01, 0.01)); - fullinit.insert(PointKey(0), Point2(5.0/sqrt(2.0), 5.0/sqrt(2.0))); - fullinit.insert(PointKey(1), Point2(5.0/sqrt(2.0), -5.0/sqrt(2.0))); + init.insert((i+1), Pose2(1.01, 0.01, 0.01)); + init.insert(100, Point2(5.0/sqrt(2.0), 5.0/sqrt(2.0))); + init.insert(101, Point2(5.0/sqrt(2.0), -5.0/sqrt(2.0))); + fullinit.insert((i+1), Pose2(1.01, 0.01, 0.01)); + fullinit.insert(100, Point2(5.0/sqrt(2.0), 5.0/sqrt(2.0))); + fullinit.insert(101, Point2(5.0/sqrt(2.0), -5.0/sqrt(2.0))); isam.update(newfactors, init); ++ i; @@ -561,8 +535,8 @@ TEST(ISAM2, slamlike_solution_dogleg) fullgraph.push_back(newfactors); Values init; - init.insert(PoseKey(i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); - fullinit.insert(PoseKey(i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); + init.insert((i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); + fullinit.insert((i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); isam.update(newfactors, init); } @@ -571,13 +545,13 @@ TEST(ISAM2, slamlike_solution_dogleg) { planarSLAM::Graph newfactors; newfactors.addOdometry(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise); - newfactors.addBearingRange(i, 0, Rot2::fromAngle(M_PI/4.0 + M_PI/16.0), 4.5, brNoise); - newfactors.addBearingRange(i, 1, Rot2::fromAngle(-M_PI/4.0 + M_PI/16.0), 4.5, brNoise); + newfactors.addBearingRange(i, 100, Rot2::fromAngle(M_PI/4.0 + M_PI/16.0), 4.5, brNoise); + newfactors.addBearingRange(i, 101, Rot2::fromAngle(-M_PI/4.0 + M_PI/16.0), 4.5, brNoise); fullgraph.push_back(newfactors); Values init; - init.insert(PoseKey(i+1), Pose2(6.9, 0.1, 0.01)); - fullinit.insert(PoseKey(i+1), Pose2(6.9, 0.1, 0.01)); + init.insert((i+1), Pose2(6.9, 0.1, 0.01)); + fullinit.insert((i+1), Pose2(6.9, 0.1, 0.01)); isam.update(newfactors, init); ++ i; @@ -618,19 +592,6 @@ TEST(ISAM2, slamlike_solution_dogleg) /* ************************************************************************* */ TEST(ISAM2, slamlike_solution_gaussnewton_qr) { - -// SETDEBUG("ISAM2 update", true); -// SETDEBUG("ISAM2 update verbose", true); -// SETDEBUG("ISAM2 recalculate", true); - - // Pose and landmark key types from planarSLAM - using planarSLAM::PoseKey; - using planarSLAM::PointKey; - - // Set up parameters - SharedDiagonal odoNoise = sharedSigmas(Vector_(3, 0.1, 0.1, M_PI/100.0)); - SharedDiagonal brNoise = sharedSigmas(Vector_(2, M_PI/100.0, 0.1)); - // These variables will be reused and accumulate factors and values ISAM2 isam(ISAM2Params(ISAM2GaussNewtonParams(0.001), 0.0, 0, false, false, ISAM2Params::QR)); Values fullinit; @@ -646,8 +607,8 @@ TEST(ISAM2, slamlike_solution_gaussnewton_qr) fullgraph.push_back(newfactors); Values init; - init.insert(PoseKey(0), Pose2(0.01, 0.01, 0.01)); - fullinit.insert(PoseKey(0), Pose2(0.01, 0.01, 0.01)); + init.insert((0), Pose2(0.01, 0.01, 0.01)); + fullinit.insert((0), Pose2(0.01, 0.01, 0.01)); isam.update(newfactors, init); } @@ -661,8 +622,8 @@ TEST(ISAM2, slamlike_solution_gaussnewton_qr) fullgraph.push_back(newfactors); Values init; - init.insert(PoseKey(i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); - fullinit.insert(PoseKey(i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); + init.insert((i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); + fullinit.insert((i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); isam.update(newfactors, init); } @@ -671,17 +632,17 @@ TEST(ISAM2, slamlike_solution_gaussnewton_qr) { planarSLAM::Graph newfactors; newfactors.addOdometry(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise); - newfactors.addBearingRange(i, 0, Rot2::fromAngle(M_PI/4.0), 5.0, brNoise); - newfactors.addBearingRange(i, 1, Rot2::fromAngle(-M_PI/4.0), 5.0, brNoise); + newfactors.addBearingRange(i, 100, Rot2::fromAngle(M_PI/4.0), 5.0, brNoise); + newfactors.addBearingRange(i, 101, Rot2::fromAngle(-M_PI/4.0), 5.0, brNoise); fullgraph.push_back(newfactors); Values init; - init.insert(PoseKey(i+1), Pose2(1.01, 0.01, 0.01)); - init.insert(PointKey(0), Point2(5.0/sqrt(2.0), 5.0/sqrt(2.0))); - init.insert(PointKey(1), Point2(5.0/sqrt(2.0), -5.0/sqrt(2.0))); - fullinit.insert(PoseKey(i+1), Pose2(1.01, 0.01, 0.01)); - fullinit.insert(PointKey(0), Point2(5.0/sqrt(2.0), 5.0/sqrt(2.0))); - fullinit.insert(PointKey(1), Point2(5.0/sqrt(2.0), -5.0/sqrt(2.0))); + init.insert((i+1), Pose2(1.01, 0.01, 0.01)); + init.insert(100, Point2(5.0/sqrt(2.0), 5.0/sqrt(2.0))); + init.insert(101, Point2(5.0/sqrt(2.0), -5.0/sqrt(2.0))); + fullinit.insert((i+1), Pose2(1.01, 0.01, 0.01)); + fullinit.insert(100, Point2(5.0/sqrt(2.0), 5.0/sqrt(2.0))); + fullinit.insert(101, Point2(5.0/sqrt(2.0), -5.0/sqrt(2.0))); isam.update(newfactors, init); ++ i; @@ -694,8 +655,8 @@ TEST(ISAM2, slamlike_solution_gaussnewton_qr) fullgraph.push_back(newfactors); Values init; - init.insert(PoseKey(i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); - fullinit.insert(PoseKey(i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); + init.insert((i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); + fullinit.insert((i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); isam.update(newfactors, init); } @@ -704,13 +665,13 @@ TEST(ISAM2, slamlike_solution_gaussnewton_qr) { planarSLAM::Graph newfactors; newfactors.addOdometry(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise); - newfactors.addBearingRange(i, 0, Rot2::fromAngle(M_PI/4.0 + M_PI/16.0), 4.5, brNoise); - newfactors.addBearingRange(i, 1, Rot2::fromAngle(-M_PI/4.0 + M_PI/16.0), 4.5, brNoise); + newfactors.addBearingRange(i, 100, Rot2::fromAngle(M_PI/4.0 + M_PI/16.0), 4.5, brNoise); + newfactors.addBearingRange(i, 101, Rot2::fromAngle(-M_PI/4.0 + M_PI/16.0), 4.5, brNoise); fullgraph.push_back(newfactors); Values init; - init.insert(PoseKey(i+1), Pose2(6.9, 0.1, 0.01)); - fullinit.insert(PoseKey(i+1), Pose2(6.9, 0.1, 0.01)); + init.insert((i+1), Pose2(6.9, 0.1, 0.01)); + fullinit.insert((i+1), Pose2(6.9, 0.1, 0.01)); isam.update(newfactors, init); ++ i; @@ -751,19 +712,6 @@ TEST(ISAM2, slamlike_solution_gaussnewton_qr) /* ************************************************************************* */ TEST(ISAM2, slamlike_solution_dogleg_qr) { - -// SETDEBUG("ISAM2 update", true); -// SETDEBUG("ISAM2 update verbose", true); -// SETDEBUG("ISAM2 recalculate", true); - - // Pose and landmark key types from planarSLAM - using planarSLAM::PoseKey; - using planarSLAM::PointKey; - - // Set up parameters - SharedDiagonal odoNoise = sharedSigmas(Vector_(3, 0.1, 0.1, M_PI/100.0)); - SharedDiagonal brNoise = sharedSigmas(Vector_(2, M_PI/100.0, 0.1)); - // These variables will be reused and accumulate factors and values ISAM2 isam(ISAM2Params(ISAM2DoglegParams(1.0), 0.0, 0, false, false, ISAM2Params::QR)); Values fullinit; @@ -779,8 +727,8 @@ TEST(ISAM2, slamlike_solution_dogleg_qr) fullgraph.push_back(newfactors); Values init; - init.insert(PoseKey(0), Pose2(0.01, 0.01, 0.01)); - fullinit.insert(PoseKey(0), Pose2(0.01, 0.01, 0.01)); + init.insert((0), Pose2(0.01, 0.01, 0.01)); + fullinit.insert((0), Pose2(0.01, 0.01, 0.01)); isam.update(newfactors, init); } @@ -794,8 +742,8 @@ TEST(ISAM2, slamlike_solution_dogleg_qr) fullgraph.push_back(newfactors); Values init; - init.insert(PoseKey(i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); - fullinit.insert(PoseKey(i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); + init.insert((i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); + fullinit.insert((i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); isam.update(newfactors, init); } @@ -804,17 +752,17 @@ TEST(ISAM2, slamlike_solution_dogleg_qr) { planarSLAM::Graph newfactors; newfactors.addOdometry(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise); - newfactors.addBearingRange(i, 0, Rot2::fromAngle(M_PI/4.0), 5.0, brNoise); - newfactors.addBearingRange(i, 1, Rot2::fromAngle(-M_PI/4.0), 5.0, brNoise); + newfactors.addBearingRange(i, 100, Rot2::fromAngle(M_PI/4.0), 5.0, brNoise); + newfactors.addBearingRange(i, 101, Rot2::fromAngle(-M_PI/4.0), 5.0, brNoise); fullgraph.push_back(newfactors); Values init; - init.insert(PoseKey(i+1), Pose2(1.01, 0.01, 0.01)); - init.insert(PointKey(0), Point2(5.0/sqrt(2.0), 5.0/sqrt(2.0))); - init.insert(PointKey(1), Point2(5.0/sqrt(2.0), -5.0/sqrt(2.0))); - fullinit.insert(PoseKey(i+1), Pose2(1.01, 0.01, 0.01)); - fullinit.insert(PointKey(0), Point2(5.0/sqrt(2.0), 5.0/sqrt(2.0))); - fullinit.insert(PointKey(1), Point2(5.0/sqrt(2.0), -5.0/sqrt(2.0))); + init.insert((i+1), Pose2(1.01, 0.01, 0.01)); + init.insert(100, Point2(5.0/sqrt(2.0), 5.0/sqrt(2.0))); + init.insert(101, Point2(5.0/sqrt(2.0), -5.0/sqrt(2.0))); + fullinit.insert((i+1), Pose2(1.01, 0.01, 0.01)); + fullinit.insert(100, Point2(5.0/sqrt(2.0), 5.0/sqrt(2.0))); + fullinit.insert(101, Point2(5.0/sqrt(2.0), -5.0/sqrt(2.0))); isam.update(newfactors, init); ++ i; @@ -827,8 +775,8 @@ TEST(ISAM2, slamlike_solution_dogleg_qr) fullgraph.push_back(newfactors); Values init; - init.insert(PoseKey(i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); - fullinit.insert(PoseKey(i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); + init.insert((i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); + fullinit.insert((i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); isam.update(newfactors, init); } @@ -837,13 +785,13 @@ TEST(ISAM2, slamlike_solution_dogleg_qr) { planarSLAM::Graph newfactors; newfactors.addOdometry(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise); - newfactors.addBearingRange(i, 0, Rot2::fromAngle(M_PI/4.0 + M_PI/16.0), 4.5, brNoise); - newfactors.addBearingRange(i, 1, Rot2::fromAngle(-M_PI/4.0 + M_PI/16.0), 4.5, brNoise); + newfactors.addBearingRange(i, 100, Rot2::fromAngle(M_PI/4.0 + M_PI/16.0), 4.5, brNoise); + newfactors.addBearingRange(i, 101, Rot2::fromAngle(-M_PI/4.0 + M_PI/16.0), 4.5, brNoise); fullgraph.push_back(newfactors); Values init; - init.insert(PoseKey(i+1), Pose2(6.9, 0.1, 0.01)); - fullinit.insert(PoseKey(i+1), Pose2(6.9, 0.1, 0.01)); + init.insert((i+1), Pose2(6.9, 0.1, 0.01)); + fullinit.insert((i+1), Pose2(6.9, 0.1, 0.01)); isam.update(newfactors, init); ++ i; @@ -894,8 +842,8 @@ TEST(ISAM2, clone) { // Modify original isam NonlinearFactorGraph factors; - factors.add(BetweenFactor(Symbol('x',0), Symbol('x',10), - isam.calculateEstimate(Symbol('x',0)).between(isam.calculateEstimate(Symbol('x',10))), sharedUnit(3))); + factors.add(BetweenFactor(0, 10, + isam.calculateEstimate(0).between(isam.calculateEstimate(10)), sharedUnit(3))); isam.update(factors); CHECK(assert_equal(createSlamlikeISAM2(), clone2)); @@ -978,22 +926,9 @@ TEST(ISAM2, permute_cached) { /* ************************************************************************* */ TEST(ISAM2, removeFactors) { - -// SETDEBUG("ISAM2 update", true); -// SETDEBUG("ISAM2 update verbose", true); -// SETDEBUG("ISAM2 recalculate", true); - // This test builds a graph in the same way as the "slamlike" test above, but // then removes the 2nd-to-last landmark measurement - // Pose and landmark key types from planarSLAM - using planarSLAM::PoseKey; - using planarSLAM::PointKey; - - // Set up parameters - SharedDiagonal odoNoise = sharedSigmas(Vector_(3, 0.1, 0.1, M_PI/100.0)); - SharedDiagonal brNoise = sharedSigmas(Vector_(2, M_PI/100.0, 0.1)); - // These variables will be reused and accumulate factors and values ISAM2 isam(ISAM2Params(ISAM2GaussNewtonParams(0.001), 0.0, 0, false)); Values fullinit; @@ -1009,8 +944,8 @@ TEST(ISAM2, removeFactors) fullgraph.push_back(newfactors); Values init; - init.insert(PoseKey(0), Pose2(0.01, 0.01, 0.01)); - fullinit.insert(PoseKey(0), Pose2(0.01, 0.01, 0.01)); + init.insert((0), Pose2(0.01, 0.01, 0.01)); + fullinit.insert((0), Pose2(0.01, 0.01, 0.01)); isam.update(newfactors, init); } @@ -1024,8 +959,8 @@ TEST(ISAM2, removeFactors) fullgraph.push_back(newfactors); Values init; - init.insert(PoseKey(i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); - fullinit.insert(PoseKey(i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); + init.insert((i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); + fullinit.insert((i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); isam.update(newfactors, init); } @@ -1034,17 +969,17 @@ TEST(ISAM2, removeFactors) { planarSLAM::Graph newfactors; newfactors.addOdometry(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise); - newfactors.addBearingRange(i, 0, Rot2::fromAngle(M_PI/4.0), 5.0, brNoise); - newfactors.addBearingRange(i, 1, Rot2::fromAngle(-M_PI/4.0), 5.0, brNoise); + newfactors.addBearingRange(i, 100, Rot2::fromAngle(M_PI/4.0), 5.0, brNoise); + newfactors.addBearingRange(i, 101, Rot2::fromAngle(-M_PI/4.0), 5.0, brNoise); fullgraph.push_back(newfactors); Values init; - init.insert(PoseKey(i+1), Pose2(1.01, 0.01, 0.01)); - init.insert(PointKey(0), Point2(5.0/sqrt(2.0), 5.0/sqrt(2.0))); - init.insert(PointKey(1), Point2(5.0/sqrt(2.0), -5.0/sqrt(2.0))); - fullinit.insert(PoseKey(i+1), Pose2(1.01, 0.01, 0.01)); - fullinit.insert(PointKey(0), Point2(5.0/sqrt(2.0), 5.0/sqrt(2.0))); - fullinit.insert(PointKey(1), Point2(5.0/sqrt(2.0), -5.0/sqrt(2.0))); + init.insert((i+1), Pose2(1.01, 0.01, 0.01)); + init.insert(100, Point2(5.0/sqrt(2.0), 5.0/sqrt(2.0))); + init.insert(101, Point2(5.0/sqrt(2.0), -5.0/sqrt(2.0))); + fullinit.insert((i+1), Pose2(1.01, 0.01, 0.01)); + fullinit.insert(100, Point2(5.0/sqrt(2.0), 5.0/sqrt(2.0))); + fullinit.insert(101, Point2(5.0/sqrt(2.0), -5.0/sqrt(2.0))); isam.update(newfactors, init); ++ i; @@ -1057,8 +992,8 @@ TEST(ISAM2, removeFactors) fullgraph.push_back(newfactors); Values init; - init.insert(PoseKey(i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); - fullinit.insert(PoseKey(i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); + init.insert((i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); + fullinit.insert((i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); isam.update(newfactors, init); } @@ -1067,14 +1002,14 @@ TEST(ISAM2, removeFactors) { planarSLAM::Graph newfactors; newfactors.addOdometry(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise); - newfactors.addBearingRange(i, 0, Rot2::fromAngle(M_PI/4.0 + M_PI/16.0), 4.5, brNoise); - newfactors.addBearingRange(i, 1, Rot2::fromAngle(-M_PI/4.0 + M_PI/16.0), 4.5, brNoise); + newfactors.addBearingRange(i, 100, Rot2::fromAngle(M_PI/4.0 + M_PI/16.0), 4.5, brNoise); + newfactors.addBearingRange(i, 101, Rot2::fromAngle(-M_PI/4.0 + M_PI/16.0), 4.5, brNoise); fullgraph.push_back(newfactors[0]); fullgraph.push_back(newfactors[2]); // Don't add measurement on landmark 0 Values init; - init.insert(PoseKey(i+1), Pose2(6.9, 0.1, 0.01)); - fullinit.insert(PoseKey(i+1), Pose2(6.9, 0.1, 0.01)); + init.insert((i+1), Pose2(6.9, 0.1, 0.01)); + fullinit.insert((i+1), Pose2(6.9, 0.1, 0.01)); ISAM2Result result = isam.update(newfactors, init); ++ i; @@ -1119,24 +1054,11 @@ TEST(ISAM2, removeFactors) } /* ************************************************************************* */ -TEST(ISAM2, swapFactors) +TEST_UNSAFE(ISAM2, swapFactors) { - -// SETDEBUG("ISAM2 update", true); -// SETDEBUG("ISAM2 update verbose", true); -// SETDEBUG("ISAM2 recalculate", true); - // This test builds a graph in the same way as the "slamlike" test above, but // then swaps the 2nd-to-last landmark measurement with a different one - // Pose and landmark key types from planarSLAM - using planarSLAM::PoseKey; - using planarSLAM::PointKey; - - // Set up parameters - SharedDiagonal odoNoise = sharedSigmas(Vector_(3, 0.1, 0.1, M_PI/100.0)); - SharedDiagonal brNoise = sharedSigmas(Vector_(2, M_PI/100.0, 0.1)); - Values fullinit; planarSLAM::Graph fullgraph; ISAM2 isam = createSlamlikeISAM2(fullinit, fullgraph); @@ -1149,8 +1071,8 @@ TEST(ISAM2, swapFactors) fullgraph.remove(swap_idx); planarSLAM::Graph swapfactors; -// swapfactors.addBearingRange(10, 0, Rot2::fromAngle(M_PI/4.0 + M_PI/16.0), 4.5, brNoise); // original factor - swapfactors.addBearingRange(10, 0, Rot2::fromAngle(M_PI/4.0 + M_PI/16.0), 5.0, brNoise); +// swapfactors.addBearingRange(10, 100, Rot2::fromAngle(M_PI/4.0 + M_PI/16.0), 4.5, brNoise); // original factor + swapfactors.addBearingRange(10, 100, Rot2::fromAngle(M_PI/4.0 + M_PI/16.0), 5.0, brNoise); fullgraph.push_back(swapfactors); isam.update(swapfactors, Values(), toRemove); } @@ -1191,19 +1113,6 @@ TEST(ISAM2, swapFactors) /* ************************************************************************* */ TEST(ISAM2, constrained_ordering) { - -// SETDEBUG("ISAM2 update", true); -// SETDEBUG("ISAM2 update verbose", true); -// SETDEBUG("ISAM2 recalculate", true); - - // Pose and landmark key types from planarSLAM - using planarSLAM::PoseKey; - using planarSLAM::PointKey; - - // Set up parameters - SharedDiagonal odoNoise = sharedSigmas(Vector_(3, 0.1, 0.1, M_PI/100.0)); - SharedDiagonal brNoise = sharedSigmas(Vector_(2, M_PI/100.0, 0.1)); - // These variables will be reused and accumulate factors and values ISAM2 isam(ISAM2Params(ISAM2GaussNewtonParams(0.001), 0.0, 0, false)); Values fullinit; @@ -1211,8 +1120,8 @@ TEST(ISAM2, constrained_ordering) // We will constrain x3 and x4 to the end FastMap constrained; - constrained.insert(make_pair(planarSLAM::PoseKey(3), 1)); - constrained.insert(make_pair(planarSLAM::PoseKey(4), 2)); + constrained.insert(make_pair((3), 1)); + constrained.insert(make_pair((4), 2)); // i keeps track of the time step size_t i = 0; @@ -1224,8 +1133,8 @@ TEST(ISAM2, constrained_ordering) fullgraph.push_back(newfactors); Values init; - init.insert(PoseKey(0), Pose2(0.01, 0.01, 0.01)); - fullinit.insert(PoseKey(0), Pose2(0.01, 0.01, 0.01)); + init.insert((0), Pose2(0.01, 0.01, 0.01)); + fullinit.insert((0), Pose2(0.01, 0.01, 0.01)); isam.update(newfactors, init); } @@ -1239,8 +1148,8 @@ TEST(ISAM2, constrained_ordering) fullgraph.push_back(newfactors); Values init; - init.insert(PoseKey(i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); - fullinit.insert(PoseKey(i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); + init.insert((i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); + fullinit.insert((i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); if(i >= 3) isam.update(newfactors, init, FastVector(), constrained); @@ -1252,17 +1161,17 @@ TEST(ISAM2, constrained_ordering) { planarSLAM::Graph newfactors; newfactors.addOdometry(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise); - newfactors.addBearingRange(i, 0, Rot2::fromAngle(M_PI/4.0), 5.0, brNoise); - newfactors.addBearingRange(i, 1, Rot2::fromAngle(-M_PI/4.0), 5.0, brNoise); + newfactors.addBearingRange(i, 100, Rot2::fromAngle(M_PI/4.0), 5.0, brNoise); + newfactors.addBearingRange(i, 101, Rot2::fromAngle(-M_PI/4.0), 5.0, brNoise); fullgraph.push_back(newfactors); Values init; - init.insert(PoseKey(i+1), Pose2(1.01, 0.01, 0.01)); - init.insert(PointKey(0), Point2(5.0/sqrt(2.0), 5.0/sqrt(2.0))); - init.insert(PointKey(1), Point2(5.0/sqrt(2.0), -5.0/sqrt(2.0))); - fullinit.insert(PoseKey(i+1), Pose2(1.01, 0.01, 0.01)); - fullinit.insert(PointKey(0), Point2(5.0/sqrt(2.0), 5.0/sqrt(2.0))); - fullinit.insert(PointKey(1), Point2(5.0/sqrt(2.0), -5.0/sqrt(2.0))); + init.insert((i+1), Pose2(1.01, 0.01, 0.01)); + init.insert(100, Point2(5.0/sqrt(2.0), 5.0/sqrt(2.0))); + init.insert(101, Point2(5.0/sqrt(2.0), -5.0/sqrt(2.0))); + fullinit.insert((i+1), Pose2(1.01, 0.01, 0.01)); + fullinit.insert(100, Point2(5.0/sqrt(2.0), 5.0/sqrt(2.0))); + fullinit.insert(101, Point2(5.0/sqrt(2.0), -5.0/sqrt(2.0))); isam.update(newfactors, init, FastVector(), constrained); ++ i; @@ -1275,8 +1184,8 @@ TEST(ISAM2, constrained_ordering) fullgraph.push_back(newfactors); Values init; - init.insert(PoseKey(i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); - fullinit.insert(PoseKey(i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); + init.insert((i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); + fullinit.insert((i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); isam.update(newfactors, init, FastVector(), constrained); } @@ -1285,13 +1194,13 @@ TEST(ISAM2, constrained_ordering) { planarSLAM::Graph newfactors; newfactors.addOdometry(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise); - newfactors.addBearingRange(i, 0, Rot2::fromAngle(M_PI/4.0 + M_PI/16.0), 4.5, brNoise); - newfactors.addBearingRange(i, 1, Rot2::fromAngle(-M_PI/4.0 + M_PI/16.0), 4.5, brNoise); + newfactors.addBearingRange(i, 100, Rot2::fromAngle(M_PI/4.0 + M_PI/16.0), 4.5, brNoise); + newfactors.addBearingRange(i, 101, Rot2::fromAngle(-M_PI/4.0 + M_PI/16.0), 4.5, brNoise); fullgraph.push_back(newfactors); Values init; - init.insert(PoseKey(i+1), Pose2(6.9, 0.1, 0.01)); - fullinit.insert(PoseKey(i+1), Pose2(6.9, 0.1, 0.01)); + init.insert((i+1), Pose2(6.9, 0.1, 0.01)); + fullinit.insert((i+1), Pose2(6.9, 0.1, 0.01)); isam.update(newfactors, init, FastVector(), constrained); ++ i; @@ -1301,7 +1210,7 @@ TEST(ISAM2, constrained_ordering) EXPECT(isam_check(fullgraph, fullinit, isam)); // Check that x3 and x4 are last, but either can come before the other - EXPECT(isam.getOrdering()[planarSLAM::PoseKey(3)] == 12 && isam.getOrdering()[planarSLAM::PoseKey(4)] == 13); + EXPECT(isam.getOrdering()[(3)] == 12 && isam.getOrdering()[(4)] == 13); // Check gradient at each node typedef ISAM2::sharedClique sharedClique; diff --git a/tests/testGaussianJunctionTreeB.cpp b/tests/testGaussianJunctionTreeB.cpp index 074693123..03e2d27d3 100644 --- a/tests/testGaussianJunctionTreeB.cpp +++ b/tests/testGaussianJunctionTreeB.cpp @@ -15,9 +15,20 @@ * @author nikai */ -#include -#include +#include +#include +#include +#include +#include +#include +#include +#include +#include #include +#include +#include + +#include #include #include // for operator += @@ -25,23 +36,14 @@ #include using namespace boost::assign; -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include +#include using namespace std; using namespace gtsam; using namespace example; -Key kx(size_t i) { return Symbol('x',i); } -Key kl(size_t i) { return Symbol('l',i); } +using symbol_shorthand::X; +using symbol_shorthand::L; /* ************************************************************************* * Bayes tree for smoother with "nested dissection" ordering: @@ -53,20 +55,20 @@ Key kl(size_t i) { return Symbol('l',i); } TEST( GaussianJunctionTree, constructor2 ) { // create a graph - Ordering ordering; ordering += kx(1),kx(3),kx(5),kx(7),kx(2),kx(6),kx(4); + Ordering ordering; ordering += X(1),X(3),X(5),X(7),X(2),X(6),X(4); GaussianFactorGraph fg = createSmoother(7, ordering).first; // create an ordering GaussianJunctionTree actual(fg); - vector frontal1; frontal1 += ordering[kx(5)], ordering[kx(6)], ordering[kx(4)]; - vector frontal2; frontal2 += ordering[kx(3)], ordering[kx(2)]; - vector frontal3; frontal3 += ordering[kx(1)]; - vector frontal4; frontal4 += ordering[kx(7)]; + vector frontal1; frontal1 += ordering[X(5)], ordering[X(6)], ordering[X(4)]; + vector frontal2; frontal2 += ordering[X(3)], ordering[X(2)]; + vector frontal3; frontal3 += ordering[X(1)]; + vector frontal4; frontal4 += ordering[X(7)]; vector sep1; - vector sep2; sep2 += ordering[kx(4)]; - vector sep3; sep3 += ordering[kx(2)]; - vector sep4; sep4 += ordering[kx(6)]; + vector sep2; sep2 += ordering[X(4)]; + vector sep3; sep3 += ordering[X(2)]; + vector sep4; sep4 += ordering[X(6)]; EXPECT(assert_equal(frontal1, actual.root()->frontal)); EXPECT(assert_equal(sep1, actual.root()->separator)); LONGS_EQUAL(5, actual.root()->size()); @@ -101,7 +103,7 @@ TEST( GaussianJunctionTree, optimizeMultiFrontal ) VectorValues expected(vector(7,2)); // expected solution Vector v = Vector_(2, 0., 0.); for (int i=1; i<=7; i++) - expected[ordering[Symbol('x',i)]] = v; + expected[ordering[X(i)]] = v; EXPECT(assert_equal(expected,actual)); } @@ -111,7 +113,7 @@ TEST( GaussianJunctionTree, optimizeMultiFrontal2) // create a graph example::Graph nlfg = createNonlinearFactorGraph(); Values noisy = createNoisyValues(); - Ordering ordering; ordering += kx(1),kx(2),kl(1); + Ordering ordering; ordering += X(1),X(2),L(1); GaussianFactorGraph fg = *nlfg.linearize(noisy, ordering); // optimize the graph @@ -125,9 +127,6 @@ TEST( GaussianJunctionTree, optimizeMultiFrontal2) /* ************************************************************************* */ TEST(GaussianJunctionTree, slamlike) { - using planarSLAM::PoseKey; - using planarSLAM::PointKey; - Values init; planarSLAM::Graph newfactors; planarSLAM::Graph fullgraph; @@ -137,39 +136,39 @@ TEST(GaussianJunctionTree, slamlike) { size_t i = 0; newfactors = planarSLAM::Graph(); - newfactors.addPrior(0, Pose2(0.0, 0.0, 0.0), odoNoise); - init.insert(PoseKey(0), Pose2(0.01, 0.01, 0.01)); + newfactors.addPrior(X(0), Pose2(0.0, 0.0, 0.0), odoNoise); + init.insert(X(0), Pose2(0.01, 0.01, 0.01)); fullgraph.push_back(newfactors); for( ; i<5; ++i) { newfactors = planarSLAM::Graph(); - newfactors.addOdometry(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise); - init.insert(PoseKey(i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); + newfactors.addOdometry(X(i), X(i+1), Pose2(1.0, 0.0, 0.0), odoNoise); + init.insert(X(i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); fullgraph.push_back(newfactors); } newfactors = planarSLAM::Graph(); - newfactors.addOdometry(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise); - newfactors.addBearingRange(i, 0, Rot2::fromAngle(M_PI/4.0), 5.0, brNoise); - newfactors.addBearingRange(i, 1, Rot2::fromAngle(-M_PI/4.0), 5.0, brNoise); - init.insert(PoseKey(i+1), Pose2(1.01, 0.01, 0.01)); - init.insert(PointKey(0), Point2(5.0/sqrt(2.0), 5.0/sqrt(2.0))); - init.insert(PointKey(1), Point2(5.0/sqrt(2.0), -5.0/sqrt(2.0))); + newfactors.addOdometry(X(i), X(i+1), Pose2(1.0, 0.0, 0.0), odoNoise); + newfactors.addBearingRange(X(i), L(0), Rot2::fromAngle(M_PI/4.0), 5.0, brNoise); + newfactors.addBearingRange(X(i), L(1), Rot2::fromAngle(-M_PI/4.0), 5.0, brNoise); + init.insert(X(i+1), Pose2(1.01, 0.01, 0.01)); + init.insert(L(0), Point2(5.0/sqrt(2.0), 5.0/sqrt(2.0))); + init.insert(L(1), Point2(5.0/sqrt(2.0), -5.0/sqrt(2.0))); fullgraph.push_back(newfactors); ++ i; for( ; i<5; ++i) { newfactors = planarSLAM::Graph(); - newfactors.addOdometry(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise); - init.insert(PoseKey(i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); + newfactors.addOdometry(X(i), X(i+1), Pose2(1.0, 0.0, 0.0), odoNoise); + init.insert(X(i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); fullgraph.push_back(newfactors); } newfactors = planarSLAM::Graph(); - newfactors.addOdometry(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise); - newfactors.addBearingRange(i, 0, Rot2::fromAngle(M_PI/4.0 + M_PI/16.0), 4.5, brNoise); - newfactors.addBearingRange(i, 1, Rot2::fromAngle(-M_PI/4.0 + M_PI/16.0), 4.5, brNoise); - init.insert(PoseKey(i+1), Pose2(6.9, 0.1, 0.01)); + newfactors.addOdometry(X(i), X(i+1), Pose2(1.0, 0.0, 0.0), odoNoise); + newfactors.addBearingRange(X(i), L(0), Rot2::fromAngle(M_PI/4.0 + M_PI/16.0), 4.5, brNoise); + newfactors.addBearingRange(X(i), L(1), Rot2::fromAngle(-M_PI/4.0 + M_PI/16.0), 4.5, brNoise); + init.insert(X(i+1), Pose2(6.9, 0.1, 0.01)); fullgraph.push_back(newfactors); ++ i; @@ -195,15 +194,15 @@ TEST(GaussianJunctionTree, simpleMarginal) { // Create a simple graph pose2SLAM::Graph fg; - fg.addPrior(0, Pose2(), sharedSigma(3, 10.0)); - fg.addOdometry(0, 1, Pose2(1.0, 0.0, 0.0), sharedSigmas(Vector_(3, 10.0, 1.0, 1.0))); + fg.addPrior(X(0), Pose2(), sharedSigma(3, 10.0)); + fg.addOdometry(X(0), X(1), Pose2(1.0, 0.0, 0.0), sharedSigmas(Vector_(3, 10.0, 1.0, 1.0))); Values init; - init.insert(pose2SLAM::PoseKey(0), Pose2()); - init.insert(pose2SLAM::PoseKey(1), Pose2(1.0, 0.0, 0.0)); + init.insert(X(0), Pose2()); + init.insert(X(1), Pose2(1.0, 0.0, 0.0)); Ordering ordering; - ordering += kx(1), kx(0); + ordering += X(1), X(0); GaussianFactorGraph gfg = *fg.linearize(init, ordering); diff --git a/tests/testGraph.cpp b/tests/testGraph.cpp index 6ab543d1e..c75c42b49 100644 --- a/tests/testGraph.cpp +++ b/tests/testGraph.cpp @@ -16,38 +16,34 @@ * @brief unit test for graph-inl.h */ -#include +#include +#include + +#include + #include #include // for operator += using namespace boost::assign; -#include - -// TODO: DANGEROUS, create shared pointers -#define GTSAM_MAGIC_GAUSSIAN 3 - -#include -#include +#include using namespace std; using namespace gtsam; -Key kx(size_t i) { return Symbol('x',i); } - /* ************************************************************************* */ // x1 -> x2 // -> x3 -> x4 // -> x5 TEST ( Ordering, predecessorMap2Keys ) { PredecessorMap p_map; - p_map.insert(kx(1),kx(1)); - p_map.insert(kx(2),kx(1)); - p_map.insert(kx(3),kx(1)); - p_map.insert(kx(4),kx(3)); - p_map.insert(kx(5),kx(1)); + p_map.insert(1,1); + p_map.insert(2,1); + p_map.insert(3,1); + p_map.insert(4,3); + p_map.insert(5,1); list expected; - expected += kx(4),kx(5),kx(3),kx(2),kx(1);//PoseKey(4), PoseKey(5), PoseKey(3), PoseKey(2), PoseKey(1); + expected += 4,5,3,2,1; list actual = predecessorMap2Keys(p_map); LONGS_EQUAL(expected.size(), actual.size()); @@ -67,20 +63,20 @@ TEST( Graph, predecessorMap2Graph ) map key2vertex; PredecessorMap p_map; - p_map.insert(kx(1), kx(2)); - p_map.insert(kx(2), kx(2)); - p_map.insert(kx(3), kx(2)); - boost::tie(graph, root, key2vertex) = predecessorMap2Graph, SVertex, Key>(p_map); + p_map.insert(1, 2); + p_map.insert(2, 2); + p_map.insert(3, 2); + tie(graph, root, key2vertex) = predecessorMap2Graph, SVertex, Key>(p_map); LONGS_EQUAL(3, boost::num_vertices(graph)); - CHECK(root == key2vertex[kx(2)]); + CHECK(root == key2vertex[2]); } /* ************************************************************************* */ TEST( Graph, composePoses ) { pose2SLAM::Graph graph; - Matrix cov = eye(3); + SharedNoiseModel cov = SharedNoiseModel::Unit(3); Pose2 p1(1.0, 2.0, 0.3), p2(4.0, 5.0, 0.6), p3(7.0, 8.0, 0.9), p4(2.0, 2.0, 2.9); Pose2 p12=p1.between(p2), p23=p2.between(p3), p43=p4.between(p3); graph.addOdometry(1,2, p12, cov); @@ -88,10 +84,10 @@ TEST( Graph, composePoses ) graph.addOdometry(4,3, p43, cov); PredecessorMap tree; - tree.insert(pose2SLAM::PoseKey(1),pose2SLAM::PoseKey(2)); - tree.insert(pose2SLAM::PoseKey(2),pose2SLAM::PoseKey(2)); - tree.insert(pose2SLAM::PoseKey(3),pose2SLAM::PoseKey(2)); - tree.insert(pose2SLAM::PoseKey(4),pose2SLAM::PoseKey(3)); + tree.insert(1,2); + tree.insert(2,2); + tree.insert(3,2); + tree.insert(4,3); Pose2 rootPose = p2; @@ -99,10 +95,10 @@ TEST( Graph, composePoses ) Pose2, Key> (graph, tree, rootPose); Values expected; - expected.insert(pose2SLAM::PoseKey(1), p1); - expected.insert(pose2SLAM::PoseKey(2), p2); - expected.insert(pose2SLAM::PoseKey(3), p3); - expected.insert(pose2SLAM::PoseKey(4), p4); + expected.insert(1, p1); + expected.insert(2, p2); + expected.insert(3, p3); + expected.insert(4, p4); LONGS_EQUAL(4, actual->size()); CHECK(assert_equal(expected, *actual)); diff --git a/tests/testInferenceB.cpp b/tests/testInferenceB.cpp index d399f6eac..c054b9b6a 100644 --- a/tests/testInferenceB.cpp +++ b/tests/testInferenceB.cpp @@ -17,6 +17,7 @@ #include +#include #include #include #include @@ -25,6 +26,10 @@ using namespace std; using namespace gtsam; +// Convenience for named keys +using symbol_shorthand::X; +using symbol_shorthand::L; + /* ************************************************************************* */ // The tests below test the *generic* inference algorithms. Some of these have // specialized versions in the derived classes GaussianFactorGraph etc... @@ -52,23 +57,23 @@ TEST( inference, marginals2) SharedDiagonal poseModel(sharedSigma(3, 0.1)); SharedDiagonal pointModel(sharedSigma(3, 0.1)); - fg.addPrior(0, Pose2(), poseModel); - fg.addOdometry(0, 1, Pose2(1.0,0.0,0.0), poseModel); - fg.addOdometry(1, 2, Pose2(1.0,0.0,0.0), poseModel); - fg.addBearingRange(0, 0, Rot2(), 1.0, pointModel); - fg.addBearingRange(1, 0, Rot2(), 1.0, pointModel); - fg.addBearingRange(2, 0, Rot2(), 1.0, pointModel); + fg.addPrior(X(0), Pose2(), poseModel); + fg.addOdometry(X(0), X(1), Pose2(1.0,0.0,0.0), poseModel); + fg.addOdometry(X(1), X(2), Pose2(1.0,0.0,0.0), poseModel); + fg.addBearingRange(X(0), L(0), Rot2(), 1.0, pointModel); + fg.addBearingRange(X(1), L(0), Rot2(), 1.0, pointModel); + fg.addBearingRange(X(2), L(0), Rot2(), 1.0, pointModel); Values init; - init.insert(planarSLAM::PoseKey(0), Pose2(0.0,0.0,0.0)); - init.insert(planarSLAM::PoseKey(1), Pose2(1.0,0.0,0.0)); - init.insert(planarSLAM::PoseKey(2), Pose2(2.0,0.0,0.0)); - init.insert(planarSLAM::PointKey(0), Point2(1.0,1.0)); + init.insert(X(0), Pose2(0.0,0.0,0.0)); + init.insert(X(1), Pose2(1.0,0.0,0.0)); + init.insert(X(2), Pose2(2.0,0.0,0.0)); + init.insert(L(0), Point2(1.0,1.0)); Ordering ordering(*fg.orderingCOLAMD(init)); FactorGraph::shared_ptr gfg(fg.linearize(init, ordering)); GaussianMultifrontalSolver solver(*gfg); - solver.marginalFactor(ordering[planarSLAM::PointKey(0)]); + solver.marginalFactor(ordering[L(0)]); } /* ************************************************************************* */ diff --git a/tests/testMarginals.cpp b/tests/testMarginals.cpp index 1563e395e..e3bb9e09f 100644 --- a/tests/testMarginals.cpp +++ b/tests/testMarginals.cpp @@ -51,17 +51,17 @@ TEST(Marginals, planarSLAMmarginals) { /* add prior */ // gaussian for prior - SharedDiagonal prior_model = noiseModel::Diagonal::Sigmas(Vector_(3, 0.3, 0.3, 0.1)); - Pose2 prior_measurement(0.0, 0.0, 0.0); // prior at origin - graph.add(PriorFactor(x1, prior_measurement, prior_model)); // add the factor to the graph + SharedDiagonal priorNoise = noiseModel::Diagonal::Sigmas(Vector_(3, 0.3, 0.3, 0.1)); + Pose2 priorMean(0.0, 0.0, 0.0); // prior at origin + graph.add(PriorFactor(x1, priorMean, priorNoise)); // add the factor to the graph /* add odometry */ // general noisemodel for odometry - SharedDiagonal odom_model = noiseModel::Diagonal::Sigmas(Vector_(3, 0.2, 0.2, 0.1)); - Pose2 odom_measurement(2.0, 0.0, 0.0); // create a measurement for both factors (the same in this case) + SharedDiagonal odometryNoise = noiseModel::Diagonal::Sigmas(Vector_(3, 0.2, 0.2, 0.1)); + Pose2 odometry(2.0, 0.0, 0.0); // create a measurement for both factors (the same in this case) // create between factors to represent odometry - graph.add(BetweenFactor(x1, x2, odom_measurement, odom_model)); - graph.add(BetweenFactor(x2, x3, odom_measurement, odom_model)); + graph.add(BetweenFactor(x1, x2, odometry, odometryNoise)); + graph.add(BetweenFactor(x2, x3, odometry, odometryNoise)); /* add measurements */ // general noisemodel for measurements diff --git a/tests/testNonlinearEquality.cpp b/tests/testNonlinearEquality.cpp index 94ab58831..2b35e9f60 100644 --- a/tests/testNonlinearEquality.cpp +++ b/tests/testNonlinearEquality.cpp @@ -14,15 +14,16 @@ * @author Alex Cunningham */ -#include - -#include #include #include #include +#include #include #include #include +#include + +#include using namespace std; using namespace gtsam; @@ -535,13 +536,13 @@ TEST (testNonlinearEqualityConstraint, stereo_constrained ) { VGraph graph; // create equality constraints for poses - graph.addPoseConstraint(1, camera1.pose()); - graph.addPoseConstraint(2, camera2.pose()); + graph.addPoseConstraint(x1, camera1.pose()); + graph.addPoseConstraint(x2, camera2.pose()); // create factors SharedDiagonal vmodel = noiseModel::Unit::Create(3); - graph.addMeasurement(camera1.project(landmark), vmodel, 1, 1, shK); - graph.addMeasurement(camera2.project(landmark), vmodel, 2, 2, shK); + graph.addMeasurement(camera1.project(landmark), vmodel, x1, l1, shK); + graph.addMeasurement(camera2.project(landmark), vmodel, x2, l2, shK); // add equality constraint graph.add(Point3Equality(l1, l2)); diff --git a/tests/testNonlinearFactor.cpp b/tests/testNonlinearFactor.cpp index d5e91d0d7..e203bcf94 100644 --- a/tests/testNonlinearFactor.cpp +++ b/tests/testNonlinearFactor.cpp @@ -32,13 +32,15 @@ #include #include #include +#include using namespace std; using namespace gtsam; using namespace example; -using simulated2D::PoseKey; -using simulated2D::PointKey; +// Convenience for named keys +using symbol_shorthand::X; +using symbol_shorthand::L; typedef boost::shared_ptr shared_nlf; @@ -49,11 +51,11 @@ TEST( NonlinearFactor, equals ) // create two nonlinear2 factors Point2 z3(0.,-1.); - simulated2D::Measurement f0(z3, sigma, PoseKey(1),PointKey(1)); + simulated2D::Measurement f0(z3, sigma, X(1),L(1)); // measurement between x2 and l1 Point2 z4(-1.5, -1.); - simulated2D::Measurement f1(z4, sigma, PoseKey(2),PointKey(1)); + simulated2D::Measurement f1(z4, sigma, X(2),L(1)); CHECK(assert_equal(f0,f0)); CHECK(f0.equals(f0)); @@ -199,16 +201,16 @@ TEST( NonlinearFactor, linearize_constraint1 ) SharedDiagonal constraint = noiseModel::Constrained::MixedSigmas(sigmas); Point2 mu(1., -1.); - Graph::sharedFactor f0(new simulated2D::Prior(mu, constraint, PoseKey(1))); + Graph::sharedFactor f0(new simulated2D::Prior(mu, constraint, X(1))); Values config; - config.insert(simulated2D::PoseKey(1), Point2(1.0, 2.0)); + config.insert(X(1), Point2(1.0, 2.0)); GaussianFactor::shared_ptr actual = f0->linearize(config, *config.orderingArbitrary()); // create expected Ordering ord(*config.orderingArbitrary()); Vector b = Vector_(2, 0., -3.); - JacobianFactor expected(ord[PoseKey(1)], Matrix_(2,2, 5.0, 0.0, 0.0, 1.0), b, constraint); + JacobianFactor expected(ord[X(1)], Matrix_(2,2, 5.0, 0.0, 0.0, 1.0), b, constraint); CHECK(assert_equal((const GaussianFactor&)expected, *actual)); } @@ -219,18 +221,18 @@ TEST( NonlinearFactor, linearize_constraint2 ) SharedDiagonal constraint = noiseModel::Constrained::MixedSigmas(sigmas); Point2 z3(1.,-1.); - simulated2D::Measurement f0(z3, constraint, PoseKey(1),PointKey(1)); + simulated2D::Measurement f0(z3, constraint, X(1),L(1)); Values config; - config.insert(simulated2D::PoseKey(1), Point2(1.0, 2.0)); - config.insert(simulated2D::PointKey(1), Point2(5.0, 4.0)); + config.insert(X(1), Point2(1.0, 2.0)); + config.insert(L(1), Point2(5.0, 4.0)); GaussianFactor::shared_ptr actual = f0.linearize(config, *config.orderingArbitrary()); // create expected Ordering ord(*config.orderingArbitrary()); Matrix A = Matrix_(2,2, 5.0, 0.0, 0.0, 1.0); Vector b = Vector_(2, -15., -3.); - JacobianFactor expected(ord[PoseKey(1)], -1*A, ord[PointKey(1)], A, b, constraint); + JacobianFactor expected(ord[X(1)], -1*A, ord[L(1)], A, b, constraint); CHECK(assert_equal((const GaussianFactor&)expected, *actual)); } @@ -238,7 +240,7 @@ TEST( NonlinearFactor, linearize_constraint2 ) class TestFactor4 : public NoiseModelFactor4 { public: typedef NoiseModelFactor4 Base; - TestFactor4() : Base(sharedSigmas(Vector_(1, 2.0)), PoseKey(1), PoseKey(2), PoseKey(3), PoseKey(4)) {} + TestFactor4() : Base(sharedSigmas(Vector_(1, 2.0)), X(1), X(2), X(3), X(4)) {} virtual Vector evaluateError(const LieVector& x1, const LieVector& x2, const LieVector& x3, const LieVector& x4, @@ -262,13 +264,13 @@ public: TEST(NonlinearFactor, NoiseModelFactor4) { TestFactor4 tf; Values tv; - tv.insert(PoseKey(1), LieVector(1, 1.0)); - tv.insert(PoseKey(2), LieVector(1, 2.0)); - tv.insert(PoseKey(3), LieVector(1, 3.0)); - tv.insert(PoseKey(4), LieVector(1, 4.0)); + tv.insert(X(1), LieVector(1, 1.0)); + tv.insert(X(2), LieVector(1, 2.0)); + tv.insert(X(3), LieVector(1, 3.0)); + tv.insert(X(4), LieVector(1, 4.0)); EXPECT(assert_equal(Vector_(1, 10.0), tf.unwhitenedError(tv))); DOUBLES_EQUAL(25.0/2.0, tf.error(tv), 1e-9); - Ordering ordering; ordering += PoseKey(1), PoseKey(2), PoseKey(3), PoseKey(4); + Ordering ordering; ordering += X(1), X(2), X(3), X(4); JacobianFactor jf(*boost::dynamic_pointer_cast(tf.linearize(tv, ordering))); LONGS_EQUAL(jf.keys()[0], 0); LONGS_EQUAL(jf.keys()[1], 1); @@ -285,7 +287,7 @@ TEST(NonlinearFactor, NoiseModelFactor4) { class TestFactor5 : public NoiseModelFactor5 { public: typedef NoiseModelFactor5 Base; - TestFactor5() : Base(sharedSigmas(Vector_(1, 2.0)), PoseKey(1), PoseKey(2), PoseKey(3), PoseKey(4), PoseKey(5)) {} + TestFactor5() : Base(sharedSigmas(Vector_(1, 2.0)), X(1), X(2), X(3), X(4), X(5)) {} virtual Vector evaluateError(const X1& x1, const X2& x2, const X3& x3, const X4& x4, const X5& x5, @@ -311,14 +313,14 @@ public: TEST(NonlinearFactor, NoiseModelFactor5) { TestFactor5 tf; Values tv; - tv.insert(PoseKey(1), LieVector(1, 1.0)); - tv.insert(PoseKey(2), LieVector(1, 2.0)); - tv.insert(PoseKey(3), LieVector(1, 3.0)); - tv.insert(PoseKey(4), LieVector(1, 4.0)); - tv.insert(PoseKey(5), LieVector(1, 5.0)); + tv.insert(X(1), LieVector(1, 1.0)); + tv.insert(X(2), LieVector(1, 2.0)); + tv.insert(X(3), LieVector(1, 3.0)); + tv.insert(X(4), LieVector(1, 4.0)); + tv.insert(X(5), LieVector(1, 5.0)); EXPECT(assert_equal(Vector_(1, 15.0), tf.unwhitenedError(tv))); DOUBLES_EQUAL(56.25/2.0, tf.error(tv), 1e-9); - Ordering ordering; ordering += PoseKey(1), PoseKey(2), PoseKey(3), PoseKey(4), PoseKey(5); + Ordering ordering; ordering += X(1), X(2), X(3), X(4), X(5); JacobianFactor jf(*boost::dynamic_pointer_cast(tf.linearize(tv, ordering))); LONGS_EQUAL(jf.keys()[0], 0); LONGS_EQUAL(jf.keys()[1], 1); @@ -337,7 +339,7 @@ TEST(NonlinearFactor, NoiseModelFactor5) { class TestFactor6 : public NoiseModelFactor6 { public: typedef NoiseModelFactor6 Base; - TestFactor6() : Base(sharedSigmas(Vector_(1, 2.0)), PoseKey(1), PoseKey(2), PoseKey(3), PoseKey(4), PoseKey(5), PoseKey(6)) {} + TestFactor6() : Base(sharedSigmas(Vector_(1, 2.0)), X(1), X(2), X(3), X(4), X(5), X(6)) {} virtual Vector evaluateError(const X1& x1, const X2& x2, const X3& x3, const X4& x4, const X5& x5, const X6& x6, @@ -365,15 +367,15 @@ public: TEST(NonlinearFactor, NoiseModelFactor6) { TestFactor6 tf; Values tv; - tv.insert(PoseKey(1), LieVector(1, 1.0)); - tv.insert(PoseKey(2), LieVector(1, 2.0)); - tv.insert(PoseKey(3), LieVector(1, 3.0)); - tv.insert(PoseKey(4), LieVector(1, 4.0)); - tv.insert(PoseKey(5), LieVector(1, 5.0)); - tv.insert(PoseKey(6), LieVector(1, 6.0)); + tv.insert(X(1), LieVector(1, 1.0)); + tv.insert(X(2), LieVector(1, 2.0)); + tv.insert(X(3), LieVector(1, 3.0)); + tv.insert(X(4), LieVector(1, 4.0)); + tv.insert(X(5), LieVector(1, 5.0)); + tv.insert(X(6), LieVector(1, 6.0)); EXPECT(assert_equal(Vector_(1, 21.0), tf.unwhitenedError(tv))); DOUBLES_EQUAL(110.25/2.0, tf.error(tv), 1e-9); - Ordering ordering; ordering += PoseKey(1), PoseKey(2), PoseKey(3), PoseKey(4), PoseKey(5), PoseKey(6); + Ordering ordering; ordering += X(1), X(2), X(3), X(4), X(5), X(6); JacobianFactor jf(*boost::dynamic_pointer_cast(tf.linearize(tv, ordering))); LONGS_EQUAL(jf.keys()[0], 0); LONGS_EQUAL(jf.keys()[1], 1); @@ -395,10 +397,10 @@ TEST(NonlinearFactor, NoiseModelFactor6) { TEST( NonlinearFactor, clone_rekey ) { shared_nlf init(new TestFactor4()); - EXPECT_LONGS_EQUAL(PoseKey(1), init->keys()[0]); - EXPECT_LONGS_EQUAL(PoseKey(2), init->keys()[1]); - EXPECT_LONGS_EQUAL(PoseKey(3), init->keys()[2]); - EXPECT_LONGS_EQUAL(PoseKey(4), init->keys()[3]); + EXPECT_LONGS_EQUAL(X(1), init->keys()[0]); + EXPECT_LONGS_EQUAL(X(2), init->keys()[1]); + EXPECT_LONGS_EQUAL(X(3), init->keys()[2]); + EXPECT_LONGS_EQUAL(X(4), init->keys()[3]); // Standard clone shared_nlf actClone = init->clone(); @@ -407,24 +409,24 @@ TEST( NonlinearFactor, clone_rekey ) // Re-key factor - clones with different keys std::vector new_keys(4); - new_keys[0] = PoseKey(5); - new_keys[1] = PoseKey(6); - new_keys[2] = PoseKey(7); - new_keys[3] = PoseKey(8); + new_keys[0] = X(5); + new_keys[1] = X(6); + new_keys[2] = X(7); + new_keys[3] = X(8); shared_nlf actRekey = init->rekey(new_keys); EXPECT(actRekey.get() != init.get()); // Ensure different pointers // Ensure init is unchanged - EXPECT_LONGS_EQUAL(PoseKey(1), init->keys()[0]); - EXPECT_LONGS_EQUAL(PoseKey(2), init->keys()[1]); - EXPECT_LONGS_EQUAL(PoseKey(3), init->keys()[2]); - EXPECT_LONGS_EQUAL(PoseKey(4), init->keys()[3]); + EXPECT_LONGS_EQUAL(X(1), init->keys()[0]); + EXPECT_LONGS_EQUAL(X(2), init->keys()[1]); + EXPECT_LONGS_EQUAL(X(3), init->keys()[2]); + EXPECT_LONGS_EQUAL(X(4), init->keys()[3]); // Check new keys - EXPECT_LONGS_EQUAL(PoseKey(5), actRekey->keys()[0]); - EXPECT_LONGS_EQUAL(PoseKey(6), actRekey->keys()[1]); - EXPECT_LONGS_EQUAL(PoseKey(7), actRekey->keys()[2]); - EXPECT_LONGS_EQUAL(PoseKey(8), actRekey->keys()[3]); + EXPECT_LONGS_EQUAL(X(5), actRekey->keys()[0]); + EXPECT_LONGS_EQUAL(X(6), actRekey->keys()[1]); + EXPECT_LONGS_EQUAL(X(7), actRekey->keys()[2]); + EXPECT_LONGS_EQUAL(X(8), actRekey->keys()[3]); } /* ************************************************************************* */ diff --git a/tests/testNonlinearFactorGraph.cpp b/tests/testNonlinearFactorGraph.cpp index 4f3e7560f..d1d240a67 100644 --- a/tests/testNonlinearFactorGraph.cpp +++ b/tests/testNonlinearFactorGraph.cpp @@ -32,12 +32,13 @@ using namespace boost::assign; #include #include #include +#include using namespace gtsam; using namespace example; -Key kx(size_t i) { return Symbol('x',i); } -Key kl(size_t i) { return Symbol('l',i); } +using symbol_shorthand::X; +using symbol_shorthand::L; /* ************************************************************************* */ TEST( Graph, equals ) @@ -67,16 +68,16 @@ TEST( Graph, keys ) set actual = fg.keys(); LONGS_EQUAL(3, actual.size()); set::const_iterator it = actual.begin(); - LONGS_EQUAL(kl(1), *(it++)); - LONGS_EQUAL(kx(1), *(it++)); - LONGS_EQUAL(kx(2), *(it++)); + LONGS_EQUAL(L(1), *(it++)); + LONGS_EQUAL(X(1), *(it++)); + LONGS_EQUAL(X(2), *(it++)); } /* ************************************************************************* */ TEST( Graph, GET_ORDERING) { // Ordering expected; expected += "x1","l1","x2"; // For starting with x1,x2,l1 - Ordering expected; expected += kl(1), kx(2), kx(1); // For starting with l1,x1,x2 + Ordering expected; expected += L(1), X(2), X(1); // For starting with l1,x1,x2 Graph nlfg = createNonlinearFactorGraph(); SymbolicFactorGraph::shared_ptr symbolic; Ordering::shared_ptr ordering; @@ -122,7 +123,7 @@ TEST( Graph, rekey ) { Graph init = createNonlinearFactorGraph(); map rekey_mapping; - rekey_mapping.insert(make_pair(kl(1), kl(4))); + rekey_mapping.insert(make_pair(L(1), L(4))); Graph actRekey = init.rekey(rekey_mapping); // ensure deep clone @@ -138,8 +139,8 @@ TEST( Graph, rekey ) // updated measurements Point2 z3(0, -1), z4(-1.5, -1.); SharedDiagonal sigma0_2 = noiseModel::Isotropic::Sigma(2,0.2); - expRekey.add(simulated2D::Measurement(z3, sigma0_2, kx(1), kl(4))); - expRekey.add(simulated2D::Measurement(z4, sigma0_2, kx(2), kl(4))); + expRekey.add(simulated2D::Measurement(z3, sigma0_2, X(1), L(4))); + expRekey.add(simulated2D::Measurement(z4, sigma0_2, X(2), L(4))); EXPECT(assert_equal(expRekey, actRekey)); } diff --git a/tests/testNonlinearISAM.cpp b/tests/testNonlinearISAM.cpp index 80ed7b6b6..28926ff5d 100644 --- a/tests/testNonlinearISAM.cpp +++ b/tests/testNonlinearISAM.cpp @@ -7,6 +7,7 @@ #include #include +#include #include using namespace gtsam; @@ -54,7 +55,7 @@ TEST(testNonlinearISAM, markov_chain ) { ordering.push_back(secondLast); isam.setOrdering(ordering); - Ordering expected; expected += PoseKey(0), PoseKey(1), PoseKey(2), PoseKey(4), PoseKey(3); + Ordering expected; expected += (0), (1), (2), (4), (3); EXPECT(assert_equal(expected, isam.getOrdering())); } diff --git a/tests/testNonlinearOptimizer.cpp b/tests/testNonlinearOptimizer.cpp index eb6357fbd..7cb8bb045 100644 --- a/tests/testNonlinearOptimizer.cpp +++ b/tests/testNonlinearOptimizer.cpp @@ -17,6 +17,7 @@ #include #include +#include #include #include #include @@ -38,8 +39,8 @@ using namespace gtsam; const double tol = 1e-5; -Key kx(size_t i) { return Symbol('x',i); } -Key kl(size_t i) { return Symbol('l',i); } +using symbol_shorthand::X; +using symbol_shorthand::L; /* ************************************************************************* */ TEST( NonlinearOptimizer, iterateLM ) @@ -50,7 +51,7 @@ TEST( NonlinearOptimizer, iterateLM ) // config far from minimum Point2 x0(3,0); Values config; - config.insert(simulated2D::PoseKey(1), x0); + config.insert(X(1), x0); // normal iterate GaussNewtonParams gnParams; @@ -74,18 +75,18 @@ TEST( NonlinearOptimizer, optimize ) // test error at minimum Point2 xstar(0,0); Values cstar; - cstar.insert(simulated2D::PoseKey(1), xstar); + cstar.insert(X(1), xstar); DOUBLES_EQUAL(0.0,fg.error(cstar),0.0); // test error at initial = [(1-cos(3))^2 + (sin(3))^2]*50 = Point2 x0(3,3); Values c0; - c0.insert(simulated2D::PoseKey(1), x0); + c0.insert(X(1), x0); DOUBLES_EQUAL(199.0,fg.error(c0),1e-3); // optimize parameters Ordering ord; - ord.push_back(kx(1)); + ord.push_back(X(1)); // Gauss-Newton GaussNewtonParams gnParams; @@ -113,7 +114,7 @@ TEST( NonlinearOptimizer, SimpleLMOptimizer ) Point2 x0(3,3); Values c0; - c0.insert(simulated2D::PoseKey(1), x0); + c0.insert(X(1), x0); Values actual = LevenbergMarquardtOptimizer(fg, c0).optimize(); DOUBLES_EQUAL(0,fg.error(actual),tol); @@ -126,7 +127,7 @@ TEST( NonlinearOptimizer, SimpleGNOptimizer ) Point2 x0(3,3); Values c0; - c0.insert(simulated2D::PoseKey(1), x0); + c0.insert(X(1), x0); Values actual = GaussNewtonOptimizer(fg, c0).optimize(); DOUBLES_EQUAL(0,fg.error(actual),tol); @@ -139,7 +140,7 @@ TEST( NonlinearOptimizer, SimpleDLOptimizer ) Point2 x0(3,3); Values c0; - c0.insert(simulated2D::PoseKey(1), x0); + c0.insert(X(1), x0); Values actual = DoglegOptimizer(fg, c0).optimize(); DOUBLES_EQUAL(0,fg.error(actual),tol); @@ -157,7 +158,7 @@ TEST( NonlinearOptimizer, optimization_method ) Point2 x0(3,3); Values c0; - c0.insert(simulated2D::PoseKey(1), x0); + c0.insert(X(1), x0); Values actualMFQR = LevenbergMarquardtOptimizer(fg, c0, paramsQR).optimize(); DOUBLES_EQUAL(0,fg.error(actualMFQR),tol); @@ -170,23 +171,23 @@ TEST( NonlinearOptimizer, optimization_method ) TEST( NonlinearOptimizer, Factorization ) { Values config; - config.insert(pose2SLAM::PoseKey(1), Pose2(0.,0.,0.)); - config.insert(pose2SLAM::PoseKey(2), Pose2(1.5,0.,0.)); + config.insert(X(1), Pose2(0.,0.,0.)); + config.insert(X(2), Pose2(1.5,0.,0.)); pose2SLAM::Graph graph; - graph.addPrior(1, Pose2(0.,0.,0.), noiseModel::Isotropic::Sigma(3, 1e-10)); - graph.addOdometry(1,2, Pose2(1.,0.,0.), noiseModel::Isotropic::Sigma(3, 1)); + graph.addPrior(X(1), Pose2(0.,0.,0.), noiseModel::Isotropic::Sigma(3, 1e-10)); + graph.addOdometry(X(1),X(2), Pose2(1.,0.,0.), noiseModel::Isotropic::Sigma(3, 1)); Ordering ordering; - ordering.push_back(pose2SLAM::PoseKey(1)); - ordering.push_back(pose2SLAM::PoseKey(2)); + ordering.push_back(X(1)); + ordering.push_back(X(2)); LevenbergMarquardtOptimizer optimizer(graph, config, ordering); optimizer.iterate(); Values expected; - expected.insert(pose2SLAM::PoseKey(1), Pose2(0.,0.,0.)); - expected.insert(pose2SLAM::PoseKey(2), Pose2(1.,0.,0.)); + expected.insert(X(1), Pose2(0.,0.,0.)); + expected.insert(X(2), Pose2(1.,0.,0.)); CHECK(assert_equal(expected, optimizer.values(), 1e-5)); } @@ -201,18 +202,18 @@ TEST(NonlinearOptimizer, NullFactor) { // test error at minimum Point2 xstar(0,0); Values cstar; - cstar.insert(simulated2D::PoseKey(1), xstar); + cstar.insert(X(1), xstar); DOUBLES_EQUAL(0.0,fg.error(cstar),0.0); // test error at initial = [(1-cos(3))^2 + (sin(3))^2]*50 = Point2 x0(3,3); Values c0; - c0.insert(simulated2D::PoseKey(1), x0); + c0.insert(X(1), x0); DOUBLES_EQUAL(199.0,fg.error(c0),1e-3); // optimize parameters Ordering ord; - ord.push_back(kx(1)); + ord.push_back(X(1)); // Gauss-Newton Values actual1 = GaussNewtonOptimizer(fg, c0, ord).optimize(); diff --git a/tests/testRot3Optimization.cpp b/tests/testRot3Optimization.cpp index df2471933..3e78414e9 100644 --- a/tests/testRot3Optimization.cpp +++ b/tests/testRot3Optimization.cpp @@ -24,6 +24,7 @@ #include #include #include +#include #include #include diff --git a/tests/testSymbolicBayesNetB.cpp b/tests/testSymbolicBayesNetB.cpp index e25cf33ca..4f0d04595 100644 --- a/tests/testSymbolicBayesNetB.cpp +++ b/tests/testSymbolicBayesNetB.cpp @@ -26,23 +26,24 @@ using namespace boost::assign; #include #include #include +#include using namespace std; using namespace gtsam; using namespace example; -Key kx(size_t i) { return Symbol('x',i); } -Key kl(size_t i) { return Symbol('l',i); } +using symbol_shorthand::X; +using symbol_shorthand::L; /* ************************************************************************* */ TEST( SymbolicBayesNet, constructor ) { - Ordering o; o += kx(2),kl(1),kx(1); + Ordering o; o += X(2),L(1),X(1); // Create manually IndexConditional::shared_ptr - x2(new IndexConditional(o[kx(2)],o[kl(1)], o[kx(1)])), - l1(new IndexConditional(o[kl(1)],o[kx(1)])), - x1(new IndexConditional(o[kx(1)])); + x2(new IndexConditional(o[X(2)],o[L(1)], o[X(1)])), + l1(new IndexConditional(o[L(1)],o[X(1)])), + x1(new IndexConditional(o[X(1)])); BayesNet expected; expected.push_back(x2); expected.push_back(l1); diff --git a/tests/testSymbolicFactorGraphB.cpp b/tests/testSymbolicFactorGraphB.cpp index 9b195e0c1..8fde094ed 100644 --- a/tests/testSymbolicFactorGraphB.cpp +++ b/tests/testSymbolicFactorGraphB.cpp @@ -15,37 +15,37 @@ * @author Frank Dellaert */ -#include // for operator += -using namespace boost::assign; - -#include - #include +#include +#include #include #include #include -#include + +#include + +#include // for operator += +using namespace boost::assign; using namespace std; using namespace gtsam; -using namespace example; -Key kx(size_t i) { return Symbol('x',i); } -Key kl(size_t i) { return Symbol('l',i); } +using symbol_shorthand::X; +using symbol_shorthand::L; /* ************************************************************************* */ TEST( SymbolicFactorGraph, symbolicFactorGraph ) { - Ordering o; o += kx(1),kl(1),kx(2); + Ordering o; o += X(1),L(1),X(2); // construct expected symbolic graph SymbolicFactorGraph expected; - expected.push_factor(o[kx(1)]); - expected.push_factor(o[kx(1)],o[kx(2)]); - expected.push_factor(o[kx(1)],o[kl(1)]); - expected.push_factor(o[kx(2)],o[kl(1)]); + expected.push_factor(o[X(1)]); + expected.push_factor(o[X(1)],o[X(2)]); + expected.push_factor(o[X(1)],o[L(1)]); + expected.push_factor(o[X(2)],o[L(1)]); // construct it from the factor graph - GaussianFactorGraph factorGraph = createGaussianFactorGraph(o); + GaussianFactorGraph factorGraph = example::createGaussianFactorGraph(o); SymbolicFactorGraph actual(factorGraph); CHECK(assert_equal(expected, actual)); @@ -55,11 +55,11 @@ TEST( SymbolicFactorGraph, symbolicFactorGraph ) //TEST( SymbolicFactorGraph, findAndRemoveFactors ) //{ // // construct it from the factor graph graph -// GaussianFactorGraph factorGraph = createGaussianFactorGraph(); +// GaussianFactorGraph factorGraph = example::createGaussianFactorGraph(); // SymbolicFactorGraph actual(factorGraph); // SymbolicFactor::shared_ptr f1 = actual[0]; // SymbolicFactor::shared_ptr f3 = actual[2]; -// actual.findAndRemoveFactors(kx(2)); +// actual.findAndRemoveFactors(X(2)); // // // construct expected graph after find_factors_and_remove // SymbolicFactorGraph expected; @@ -75,17 +75,17 @@ TEST( SymbolicFactorGraph, symbolicFactorGraph ) //TEST( SymbolicFactorGraph, factors) //{ // // create a test graph -// GaussianFactorGraph factorGraph = createGaussianFactorGraph(); +// GaussianFactorGraph factorGraph = example::createGaussianFactorGraph(); // SymbolicFactorGraph fg(factorGraph); // // // ask for all factor indices connected to x1 -// list x1_factors = fg.factors(kx(1)); +// list x1_factors = fg.factors(X(1)); // int x1_indices[] = { 0, 1, 2 }; // list x1_expected(x1_indices, x1_indices + 3); // CHECK(x1_factors==x1_expected); // // // ask for all factor indices connected to x2 -// list x2_factors = fg.factors(kx(2)); +// list x2_factors = fg.factors(X(2)); // int x2_indices[] = { 1, 3 }; // list x2_expected(x2_indices, x2_indices + 2); // CHECK(x2_factors==x2_expected); @@ -95,30 +95,30 @@ TEST( SymbolicFactorGraph, symbolicFactorGraph ) //TEST( SymbolicFactorGraph, removeAndCombineFactors ) //{ // // create a test graph -// GaussianFactorGraph factorGraph = createGaussianFactorGraph(); +// GaussianFactorGraph factorGraph = example::createGaussianFactorGraph(); // SymbolicFactorGraph fg(factorGraph); // // // combine all factors connected to x1 -// SymbolicFactor::shared_ptr actual = removeAndCombineFactors(fg,kx(1)); +// SymbolicFactor::shared_ptr actual = removeAndCombineFactors(fg,X(1)); // // // check result -// SymbolicFactor expected(kl(1),kx(1),kx(2)); +// SymbolicFactor expected(L(1),X(1),X(2)); // CHECK(assert_equal(expected,*actual)); //} ///* ************************************************************************* */ //TEST( SymbolicFactorGraph, eliminateOne ) //{ -// Ordering o; o += kx(1),kl(1),kx(2); +// Ordering o; o += X(1),L(1),X(2); // // create a test graph -// GaussianFactorGraph factorGraph = createGaussianFactorGraph(o); +// GaussianFactorGraph factorGraph = example::createGaussianFactorGraph(o); // SymbolicFactorGraph fg(factorGraph); // // // eliminate -// IndexConditional::shared_ptr actual = GaussianSequentialSolver::EliminateUntil(fg, o[kx(1)]+1); +// IndexConditional::shared_ptr actual = GaussianSequentialSolver::EliminateUntil(fg, o[X(1)]+1); // // // create expected symbolic IndexConditional -// IndexConditional expected(o[kx(1)],o[kl(1)],o[kx(2)]); +// IndexConditional expected(o[X(1)],o[L(1)],o[X(2)]); // // CHECK(assert_equal(expected,*actual)); //} @@ -126,12 +126,12 @@ TEST( SymbolicFactorGraph, symbolicFactorGraph ) /* ************************************************************************* */ TEST( SymbolicFactorGraph, eliminate ) { - Ordering o; o += kx(2),kl(1),kx(1); + Ordering o; o += X(2),L(1),X(1); // create expected Chordal bayes Net - IndexConditional::shared_ptr x2(new IndexConditional(o[kx(2)], o[kl(1)], o[kx(1)])); - IndexConditional::shared_ptr l1(new IndexConditional(o[kl(1)], o[kx(1)])); - IndexConditional::shared_ptr x1(new IndexConditional(o[kx(1)])); + IndexConditional::shared_ptr x2(new IndexConditional(o[X(2)], o[L(1)], o[X(1)])); + IndexConditional::shared_ptr l1(new IndexConditional(o[L(1)], o[X(1)])); + IndexConditional::shared_ptr x1(new IndexConditional(o[X(1)])); SymbolicBayesNet expected; expected.push_back(x2); @@ -139,7 +139,7 @@ TEST( SymbolicFactorGraph, eliminate ) expected.push_back(x1); // create a test graph - GaussianFactorGraph factorGraph = createGaussianFactorGraph(o); + GaussianFactorGraph factorGraph = example::createGaussianFactorGraph(o); SymbolicFactorGraph fg(factorGraph); // eliminate it diff --git a/wrap/CMakeLists.txt b/wrap/CMakeLists.txt index 01d873bac..57a82ba8a 100644 --- a/wrap/CMakeLists.txt +++ b/wrap/CMakeLists.txt @@ -76,6 +76,12 @@ if (GTSAM_INSTALL_MATLAB_TOOLBOX) message(STATUS "Installing Matlab Toolbox Examples") file(GLOB matlab_examples "${CMAKE_SOURCE_DIR}/examples/matlab/*.m") install(FILES ${matlab_examples} DESTINATION ${GTSAM_TOOLBOX_INSTALL_PATH}/gtsam/examples) + + message(STATUS "Installing Matlab Toolbox Examples (Data)") + set(data_excludes "${CMAKE_SOURCE_DIR}/examples/Data/.svn") + file(GLOB matlab_examples_data "${CMAKE_SOURCE_DIR}/examples/Data/*.*") + list(REMOVE_ITEM matlab_examples_data ${data_excludes}) + install(FILES ${matlab_examples_data} DESTINATION ${GTSAM_TOOLBOX_INSTALL_PATH}/gtsam/examples/Data) endif (GTSAM_INSTALL_MATLAB_EXAMPLES) # Tests diff --git a/wrap/matlab.h b/wrap/matlab.h index a69d8aba4..483326720 100644 --- a/wrap/matlab.h +++ b/wrap/matlab.h @@ -106,6 +106,14 @@ mxArray* wrap(char& value) { return result; } +// specialization to unsigned char +template<> +mxArray* wrap(unsigned char& value) { + mxArray *result = scalar(mxUINT32OR64_CLASS); + *(unsigned char*)mxGetData(result) = value; + return result; +} + // specialization to bool template<> mxArray* wrap(bool& value) { @@ -227,13 +235,20 @@ bool unwrap(const mxArray* array) { return myGetScalar(array); } -// specialization to bool +// specialization to char template<> char unwrap(const mxArray* array) { checkScalar(array,"unwrap"); return myGetScalar(array); } +// specialization to unsigned char +template<> +unsigned char unwrap(const mxArray* array) { + checkScalar(array,"unwrap"); + return myGetScalar(array); +} + // specialization to int template<> int unwrap(const mxArray* array) {